mirror of https://github.com/ArduPilot/ardupilot
AP_PiccoloCAN: Constrain ESC command message rate
Use constain_int16 rather than using primitive checks
This commit is contained in:
parent
21ffc0f663
commit
8aeec6c4d1
|
@ -147,14 +147,7 @@ void AP_PiccoloCAN::loop()
|
|||
|
||||
while (true) {
|
||||
|
||||
// Calculate the output rate (in ms) based on the configured rate (in Hz)
|
||||
if (_esc_hz < PICCOLO_MSG_RATE_HZ_MIN) {
|
||||
_esc_hz = PICCOLO_MSG_RATE_HZ_MIN;
|
||||
}
|
||||
|
||||
if (_esc_hz > PICCOLO_MSG_RATE_HZ_MAX) {
|
||||
_esc_hz = PICCOLO_MSG_RATE_HZ_MAX;
|
||||
}
|
||||
_esc_hz = constrain_int16(_esc_hz, PICCOLO_MSG_RATE_HZ_MIN, PICCOLO_MSG_RATE_HZ_MAX);
|
||||
|
||||
escCmdRateMs = (uint16_t) ((float) 1000 / _esc_hz);
|
||||
|
||||
|
|
|
@ -138,7 +138,7 @@ private:
|
|||
|
||||
// Piccolo CAN parameters
|
||||
AP_Int32 _esc_bm; //! ESC selection bitmask
|
||||
AP_Int32 _esc_hz; //! ESC update rate (Hz)
|
||||
AP_Int16 _esc_hz; //! ESC update rate (Hz)
|
||||
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue