mirror of https://github.com/ArduPilot/ardupilot
HAL_VRBrain: implement force_safety_on
This commit is contained in:
parent
ffcd259b4e
commit
6da1420541
|
@ -149,6 +149,12 @@ void VRBRAINRCOutput::set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
|
|||
}
|
||||
}
|
||||
|
||||
bool VRBRAINRCOutput::force_safety_on(void)
|
||||
{
|
||||
int ret = ioctl(_pwm_fd, PWM_SERVO_SET_FORCE_SAFETY_ON, 0);
|
||||
return (ret == OK);
|
||||
}
|
||||
|
||||
void VRBRAINRCOutput::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