mirror of https://github.com/ArduPilot/ardupilot
HAL_PX4: support setting servo rate
This commit is contained in:
parent
0660873fa7
commit
319e1a4e84
|
@ -27,12 +27,15 @@ void PX4RCOutput::init(void* unused)
|
||||||
|
|
||||||
void PX4RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
|
void PX4RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||||
{
|
{
|
||||||
// no support for this yet
|
// we can't set this per channel yet
|
||||||
|
if (ioctl(_pwm_fd, PWM_SERVO_SET_UPDATE_RATE, (unsigned long)freq_hz) == 0) {
|
||||||
|
_freq_hz = freq_hz;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t PX4RCOutput::get_freq(uint8_t ch)
|
uint16_t PX4RCOutput::get_freq(uint8_t ch)
|
||||||
{
|
{
|
||||||
return 50;
|
return _freq_hz;
|
||||||
}
|
}
|
||||||
|
|
||||||
void PX4RCOutput::enable_ch(uint8_t ch)
|
void PX4RCOutput::enable_ch(uint8_t ch)
|
||||||
|
|
|
@ -21,6 +21,7 @@ public:
|
||||||
|
|
||||||
private:
|
private:
|
||||||
int _pwm_fd;
|
int _pwm_fd;
|
||||||
|
uint16_t _freq_hz;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_HAL_PX4_RCOUTPUT_H__
|
#endif // __AP_HAL_PX4_RCOUTPUT_H__
|
||||||
|
|
Loading…
Reference in New Issue