mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: added force_safety_off rcoutput function
this forces the safety switch off, enabling PWM on the IO board
This commit is contained in:
parent
89b222f1cf
commit
439a075b30
|
@ -48,6 +48,11 @@ public:
|
||||||
in the safe state
|
in the safe state
|
||||||
*/
|
*/
|
||||||
virtual void set_safety_pwm(uint32_t chmask, uint16_t period_us) {}
|
virtual void set_safety_pwm(uint32_t chmask, uint16_t period_us) {}
|
||||||
|
|
||||||
|
/*
|
||||||
|
force the safety switch off, enabling PWM output from the IO board
|
||||||
|
*/
|
||||||
|
virtual void force_safety_off(void) {}
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_HAL_RC_OUTPUT_H__
|
#endif // __AP_HAL_RC_OUTPUT_H__
|
||||||
|
|
|
@ -160,6 +160,14 @@ void PX4RCOutput::set_safety_pwm(uint32_t chmask, uint16_t period_us)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PX4RCOutput::force_safety_off(void)
|
||||||
|
{
|
||||||
|
int ret = ioctl(_pwm_fd, PWM_SERVO_SET_FORCE_SAFETY_OFF, 0);
|
||||||
|
if (ret != OK) {
|
||||||
|
hal.console->printf("Failed to force safety off\n");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void PX4RCOutput::write(uint8_t ch, uint16_t period_us)
|
void PX4RCOutput::write(uint8_t ch, uint16_t period_us)
|
||||||
{
|
{
|
||||||
if (ch >= _servo_count + _alt_servo_count) {
|
if (ch >= _servo_count + _alt_servo_count) {
|
||||||
|
|
|
@ -20,6 +20,7 @@ public:
|
||||||
uint16_t read(uint8_t ch);
|
uint16_t read(uint8_t ch);
|
||||||
void read(uint16_t* period_us, uint8_t len);
|
void read(uint16_t* period_us, uint8_t len);
|
||||||
void set_safety_pwm(uint32_t chmask, uint16_t period_us);
|
void set_safety_pwm(uint32_t chmask, uint16_t period_us);
|
||||||
|
void force_safety_off(void);
|
||||||
|
|
||||||
void _timer_tick(void);
|
void _timer_tick(void);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue