mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
HAL_PX4: implement force_safety_on
This commit is contained in:
parent
033b14db16
commit
ffcd259b4e
@ -174,6 +174,12 @@ void PX4RCOutput::set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
|
||||
}
|
||||
}
|
||||
|
||||
bool PX4RCOutput::force_safety_on(void)
|
||||
{
|
||||
int ret = ioctl(_pwm_fd, PWM_SERVO_SET_FORCE_SAFETY_ON, 0);
|
||||
return (ret == OK);
|
||||
}
|
||||
|
||||
void PX4RCOutput::force_safety_off(void)
|
||||
{
|
||||
int ret = ioctl(_pwm_fd, PWM_SERVO_SET_FORCE_SAFETY_OFF, 0);
|
||||
|
@ -21,6 +21,7 @@ public:
|
||||
void read(uint16_t* period_us, uint8_t len);
|
||||
void set_safety_pwm(uint32_t chmask, uint16_t period_us);
|
||||
void set_failsafe_pwm(uint32_t chmask, uint16_t period_us);
|
||||
bool force_safety_on(void);
|
||||
void force_safety_off(void);
|
||||
|
||||
void _timer_tick(void);
|
||||
|
Loading…
Reference in New Issue
Block a user