mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
AP_HAL_PX4: set default servo update rate only when changed
This removes the chance a small switch occurring whenever this function is called
This commit is contained in:
parent
3d13d98410
commit
687ec98e5d
@ -644,10 +644,15 @@ void PX4RCOutput::set_output_mode(enum output_mode mode)
|
|||||||
// set default output update rate
|
// set default output update rate
|
||||||
void PX4RCOutput::set_default_rate(uint16_t rate_hz)
|
void PX4RCOutput::set_default_rate(uint16_t rate_hz)
|
||||||
{
|
{
|
||||||
|
if (rate_hz != _default_rate_hz) {
|
||||||
|
// set servo update rate for first 8 pwm channels
|
||||||
ioctl(_pwm_fd, PWM_SERVO_SET_DEFAULT_UPDATE_RATE, rate_hz);
|
ioctl(_pwm_fd, PWM_SERVO_SET_DEFAULT_UPDATE_RATE, rate_hz);
|
||||||
if (_alt_fd != -1) {
|
if (_alt_fd != -1) {
|
||||||
|
// set servo update rate for auxiliary channels
|
||||||
ioctl(_alt_fd, PWM_SERVO_SET_DEFAULT_UPDATE_RATE, rate_hz);
|
ioctl(_alt_fd, PWM_SERVO_SET_DEFAULT_UPDATE_RATE, rate_hz);
|
||||||
}
|
}
|
||||||
|
_default_rate_hz = rate_hz;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
@ -82,4 +82,5 @@ private:
|
|||||||
enum AP_HAL::Util::safety_state _safety_state_request = AP_HAL::Util::SAFETY_NONE;
|
enum AP_HAL::Util::safety_state _safety_state_request = AP_HAL::Util::SAFETY_NONE;
|
||||||
uint32_t _safety_state_request_last_ms = 0;
|
uint32_t _safety_state_request_last_ms = 0;
|
||||||
void force_safety_pending_requests(void);
|
void force_safety_pending_requests(void);
|
||||||
|
uint16_t _default_rate_hz = 50;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user