Browse Source

AP_HAL: added set_safety_pwm() API

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
5e39b6fb11
  1. 6
      libraries/AP_HAL/RCOutput.h

6
libraries/AP_HAL/RCOutput.h

@ -45,6 +45,12 @@ public: @@ -45,6 +45,12 @@ public:
* array of channels. */
virtual uint16_t read(uint8_t ch) = 0;
virtual void read(uint16_t* period_us, uint8_t len) = 0;
/*
set PWM to send to a set of channels when the safety switch is
in the safe state
*/
virtual void set_safety_pwm(uint32_t chmask, uint16_t period_us) {}
};
#endif // __AP_HAL_RC_OUTPUT_H__

Loading…
Cancel
Save