AP_PiccoloCAN: fix for new param set

This commit is contained in:
Andrew Tridgell 2022-09-20 09:32:35 +10:00 committed by Peter Barker
parent 19f135b1b6
commit e4a0ea65b8
1 changed files with 1 additions and 1 deletions

View File

@ -208,7 +208,7 @@ void AP_PiccoloCAN::loop()
uint16_t servoCmdRateMs = 1000 / _srv_hz;
#if HAL_EFI_CURRAWONG_ECU_ENABLED
_ecu_hz = constrain_int16(_ecu_hz, PICCOLO_MSG_RATE_HZ_MIN, PICCOLO_MSG_RATE_HZ_MAX);
_ecu_hz.set(constrain_int16(_ecu_hz, PICCOLO_MSG_RATE_HZ_MIN, PICCOLO_MSG_RATE_HZ_MAX));
uint16_t ecuCmdRateMs = 1000 / _ecu_hz;
#endif