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)
This commit is contained in:
Randy Mackay 2021-08-09 20:48:27 +09:00 committed by Peter Barker
parent 29aed55a74
commit b399649c36
1 changed files with 1 additions and 1 deletions

View File

@ -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;