AP_PiccoloCAN: params always use set method

This commit is contained in:
Iampete1 2022-07-05 04:08:56 +01:00 committed by Peter Hall
parent 59d75813cc
commit 63e58e4fa1

View File

@ -175,12 +175,12 @@ void AP_PiccoloCAN::loop()
}
// Calculate the output rate for ESC commands
_esc_hz = constrain_int16(_esc_hz, PICCOLO_MSG_RATE_HZ_MIN, PICCOLO_MSG_RATE_HZ_MAX);
_esc_hz.set(constrain_int16(_esc_hz, PICCOLO_MSG_RATE_HZ_MIN, PICCOLO_MSG_RATE_HZ_MAX));
uint16_t escCmdRateMs = 1000 / _esc_hz;
// Calculate the output rate for servo commands
_srv_hz = constrain_int16(_srv_hz, PICCOLO_MSG_RATE_HZ_MIN, PICCOLO_MSG_RATE_HZ_MAX);
_srv_hz.set(constrain_int16(_srv_hz, PICCOLO_MSG_RATE_HZ_MIN, PICCOLO_MSG_RATE_HZ_MAX));
uint16_t servoCmdRateMs = 1000 / _srv_hz;