2013-01-04 07:25:36 -04:00
|
|
|
|
|
|
|
#ifndef __AP_HAL_PX4_RCOUTPUT_H__
|
|
|
|
#define __AP_HAL_PX4_RCOUTPUT_H__
|
|
|
|
|
|
|
|
#include <AP_HAL_PX4.h>
|
2013-01-25 04:16:28 -04:00
|
|
|
#include <systemlib/perf_counter.h>
|
2014-11-05 06:38:12 -04:00
|
|
|
#include <uORB/topics/actuator_outputs.h>
|
2014-11-20 03:31:41 -04:00
|
|
|
#include <uORB/topics/actuator_armed.h>
|
2013-01-04 07:25:36 -04:00
|
|
|
|
2013-01-22 16:29:59 -04:00
|
|
|
#define PX4_NUM_OUTPUT_CHANNELS 16
|
|
|
|
|
2013-01-04 07:25:36 -04:00
|
|
|
class PX4::PX4RCOutput : public AP_HAL::RCOutput
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
void init(void* machtnichts);
|
|
|
|
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
|
|
|
uint16_t get_freq(uint8_t ch);
|
|
|
|
void enable_ch(uint8_t ch);
|
|
|
|
void disable_ch(uint8_t ch);
|
|
|
|
void write(uint8_t ch, uint16_t period_us);
|
|
|
|
void write(uint8_t ch, uint16_t* period_us, uint8_t len);
|
|
|
|
uint16_t read(uint8_t ch);
|
|
|
|
void read(uint16_t* period_us, uint8_t len);
|
2014-01-15 07:25:50 -04:00
|
|
|
void set_safety_pwm(uint32_t chmask, uint16_t period_us);
|
2014-04-20 19:36:52 -03:00
|
|
|
void set_failsafe_pwm(uint32_t chmask, uint16_t period_us);
|
2014-09-14 05:23:58 -03:00
|
|
|
bool force_safety_on(void);
|
2014-02-11 00:56:44 -04:00
|
|
|
void force_safety_off(void);
|
2014-11-20 03:31:41 -04:00
|
|
|
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) {
|
|
|
|
_esc_pwm_min = min_pwm;
|
|
|
|
_esc_pwm_max = max_pwm;
|
|
|
|
}
|
2013-01-04 07:25:36 -04:00
|
|
|
|
2013-01-25 04:16:28 -04:00
|
|
|
void _timer_tick(void);
|
|
|
|
|
2013-01-04 07:25:36 -04:00
|
|
|
private:
|
|
|
|
int _pwm_fd;
|
2013-04-25 06:59:30 -03:00
|
|
|
int _alt_fd;
|
2013-01-05 07:45:17 -04:00
|
|
|
uint16_t _freq_hz;
|
2013-01-22 16:29:59 -04:00
|
|
|
uint16_t _period[PX4_NUM_OUTPUT_CHANNELS];
|
2013-01-25 04:16:28 -04:00
|
|
|
volatile uint8_t _max_channel;
|
|
|
|
volatile bool _need_update;
|
|
|
|
perf_counter_t _perf_rcout;
|
|
|
|
uint32_t _last_output;
|
2013-04-25 06:59:30 -03:00
|
|
|
unsigned _servo_count;
|
|
|
|
unsigned _alt_servo_count;
|
|
|
|
uint32_t _rate_mask;
|
2014-01-19 21:56:30 -04:00
|
|
|
uint16_t _enabled_channels;
|
2015-06-03 22:00:34 -03:00
|
|
|
struct {
|
|
|
|
int pwm_sub;
|
|
|
|
actuator_outputs_s outputs;
|
|
|
|
} _outputs[ORB_MULTI_MAX_INSTANCES] {};
|
2014-11-20 03:31:41 -04:00
|
|
|
actuator_armed_s _armed;
|
|
|
|
|
2015-05-31 01:49:27 -03:00
|
|
|
orb_advert_t _actuator_direct_pub = NULL;
|
|
|
|
orb_advert_t _actuator_armed_pub = NULL;
|
2015-06-06 20:07:47 -03:00
|
|
|
uint16_t _esc_pwm_min = 0;
|
|
|
|
uint16_t _esc_pwm_max = 0;
|
2014-01-19 21:56:30 -04:00
|
|
|
|
|
|
|
void _init_alt_channels(void);
|
2014-11-20 03:31:41 -04:00
|
|
|
void _publish_actuators(void);
|
|
|
|
void _arm_actuators(bool arm);
|
2013-01-04 07:25:36 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_HAL_PX4_RCOUTPUT_H__
|