From b399649c36367f0628ced564d7f957b6f3c8ccb7 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 9 Aug 2021 20:48:27 +0900 Subject: [PATCH] AP_Torqeedo: increase speed cmd at 50hz under human control the tiller/battery only sends at 3hz but in testing it is capable of at least 50hz (but not as much as 100hz) --- libraries/AP_Torqeedo/AP_Torqeedo.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Torqeedo/AP_Torqeedo.cpp b/libraries/AP_Torqeedo/AP_Torqeedo.cpp index bd68641b30..7e5ba03905 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo.cpp +++ b/libraries/AP_Torqeedo/AP_Torqeedo.cpp @@ -27,7 +27,7 @@ #define TORQEEDO_PACKET_HEADER 0xAC // communication packet header #define TORQEEDO_PACKET_FOOTER 0xAD // communication packer footer #define TORQEEDO_LOG_INTERVAL_MS 5000 // log debug info at this interval in milliseconds -#define TORQEEDO_SEND_MOTOR_SPEED_INTERVAL_US 300000 // motor speed sent every 0.3sec if connected to motor +#define TORQEEDO_SEND_MOTOR_SPEED_INTERVAL_US 20000 // motor speed sent at 50hz if connected to motor extern const AP_HAL::HAL& hal;