3 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 11 #include <drivers/drv_pwm_output.h> 12 #include <drivers/drv_hrt.h> 13 #include <drivers/drv_pwm_output.h> 14 #include <drivers/drv_sbus.h> 26 #define RCOUT_DEBUG_LATENCY 0 35 if (ioctl(
_pwm_fd, PWM_SERVO_ARM, 0) != 0) {
38 if (ioctl(
_pwm_fd, PWM_SERVO_SET_ARM_OK, 0) != 0) {
39 hal.
console->
printf(
"RCOutput: Unable to setup IO arming OK\n");
53 for (uint8_t i=0; i<ORB_MULTI_MAX_INSTANCES; i++) {
54 _outputs[i].pwm_sub = orb_subscribe_multi(ORB_ID(actuator_outputs), i);
57 #if !defined(CONFIG_ARCH_BOARD_PX4FMU_V4) 61 if (
stat(
"/dev/px4io", &st) == 0) {
82 if (ioctl(
_alt_fd, PWM_SERVO_ARM, 0) != 0) {
83 hal.
console->
printf(
"RCOutput: Unable to setup alt IO arming\n");
86 if (ioctl(
_alt_fd, PWM_SERVO_SET_ARM_OK, 0) != 0) {
87 hal.
console->
printf(
"RCOutput: Unable to setup alt IO arming OK\n");
107 if (freq_hz > 50 || freq_hz == 1) {
118 if (ioctl(fd, PWM_SERVO_SET_UPDATE_RATE, (
unsigned long)freq_hz) != 0) {
119 hal.
console->
printf(
"RCOutput: Unable to set alt rate to %uHz\n", (
unsigned)freq_hz);
136 if (freq_hz > 50 || freq_hz == 1) {
138 rate_mask |= chmask & 0xFF;
139 if (rate_mask & 0x3) {
142 if (rate_mask & 0xc) {
145 if (rate_mask & 0xF0) {
161 if (ioctl(fd, PWM_SERVO_SET_SELECT_UPDATE_RATE, rate_mask) != 0) {
162 hal.
console->
printf(
"RCOutput: Unable to set alt rate mask to 0x%x\n", (
unsigned)rate_mask);
166 ioctl(fd, PWM_SERVO_SET_UPDATE_CLOCK, 8);
182 hal.
console->
printf(
"RCOutput: Unable to get servo count\n");
191 uint32_t primary_mask = chmask & ((1UL<<
_servo_count)-1);
193 if (primary_mask &&
_pwm_fd != -1) {
196 if (alt_mask &&
_alt_fd != -1) {
245 struct pwm_output_values pwm_values;
246 memset(&pwm_values, 0,
sizeof(pwm_values));
248 if ((1UL<<i) & chmask) {
249 pwm_values.values[i] = period_us;
251 pwm_values.channel_count++;
253 int ret = ioctl(
_pwm_fd, PWM_SERVO_SET_DISARMED_PWM, (
long unsigned int)&pwm_values);
255 hal.
console->
printf(
"Failed to setup disarmed PWM for 0x%08x to %u\n", (
unsigned)chmask, period_us);
261 struct pwm_output_values pwm_values;
262 memset(&pwm_values, 0,
sizeof(pwm_values));
264 if ((1UL<<i) & chmask) {
265 pwm_values.values[i] = period_us;
267 pwm_values.channel_count++;
269 int ret = ioctl(
_pwm_fd, PWM_SERVO_SET_FAILSAFE_PWM, (
long unsigned int)&pwm_values);
271 hal.
console->
printf(
"Failed to setup failsafe PWM for 0x%08x to %u\n", (
unsigned)chmask, period_us);
299 ioctl(
_pwm_fd, PWM_SERVO_SET_FORCE_SAFETY_ON, 0);
303 ioctl(
_pwm_fd, PWM_SERVO_SET_FORCE_SAFETY_OFF, 0);
312 uint16_t desired_options = 0;
315 desired_options |= PWM_SERVO_SET_SAFETY_OPTION_DISABLE_BUTTON_OFF;
318 desired_options |= PWM_SERVO_SET_SAFETY_OPTION_DISABLE_BUTTON_ON;
321 desired_options |= PWM_SERVO_SET_SAFETY_OPTION_DISABLE_BUTTON_OFF | PWM_SERVO_SET_SAFETY_OPTION_DISABLE_BUTTON_ON;
324 if (ioctl(
_pwm_fd, PWM_SERVO_SET_SAFETY_OPTIONS, desired_options) == OK) {
385 if (period_us !=
_period[ch] ||
401 for (uint8_t i=0; i<ORB_MULTI_MAX_INSTANCES; i++) {
404 _outputs[i].outputs.output[ch] > 0) {
405 return _outputs[i].outputs.output[ch];
413 for (uint8_t i=0; i<len; i++) {
414 period_us[i] =
read(i);
429 for (uint8_t i=0; i<len; i++) {
439 if (
_armed.armed == arm) {
444 _armed.timestamp = hrt_absolute_time();
449 _armed.ready_to_arm =
true;
452 _armed.force_failsafe =
false;
496 for (
int i=to_send-1; i >= 0; i--) {
527 for (uint8_t i=0; i<ORB_MULTI_MAX_INSTANCES; i++) {
528 bool rc_updated =
false;
540 #if RCOUT_DEBUG_LATENCY 549 #if RCOUT_DEBUG_LATENCY 579 int fd =
open(
"/dev/px4io", 0);
583 for (uint8_t tries=0; tries<10; tries++) {
584 if (ioctl(fd, SBUS_SET_PROTO_VERSION, 1) != 0) {
587 if (ioctl(fd, PWM_SERVO_SET_SBUS_RATE, rate_hz) != 0) {
623 ioctl(
_pwm_fd, PWM_SERVO_SET_ONESHOT, 1);
625 ioctl(
_alt_fd, PWM_SERVO_SET_ONESHOT, 1);
637 ioctl(
_pwm_fd, PWM_SERVO_SET_ONESHOT, 0);
639 ioctl(
_alt_fd, PWM_SERVO_SET_ONESHOT, 0);
644 ioctl(
_pwm_fd, PWM_SERVO_SET_UPDATE_CLOCK, 8);
646 ioctl(
_alt_fd, PWM_SERVO_SET_UPDATE_CLOCK, 8);
658 ioctl(
_pwm_fd, PWM_SERVO_SET_DEFAULT_UPDATE_RATE, rate_hz);
661 ioctl(
_alt_fd, PWM_SERVO_SET_DEFAULT_UPDATE_RATE, rate_hz);
667 #endif // CONFIG_HAL_BOARD
bool get_soft_armed() const
void timer_tick(void) override
uint16_t _last_sent[PX4_NUM_OUTPUT_CHANNELS]
void set_output_mode(uint16_t mask, enum output_mode mode) override
void set_freq(uint32_t chmask, uint16_t freq_hz) override
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
AP_HAL::UARTDriver * console
static AP_BoardConfig * get_instance(void)
void _arm_actuators(bool arm)
perf_counter_t _perf_rcout
uint16_t read_last_sent(uint8_t ch) override
uint32_t _safety_state_request_last_ms
bool enable_px4io_sbus_out(uint16_t rate_hz) override
void disable_ch(uint8_t ch) override
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void write(uint8_t ch, uint16_t period_us) override
virtual void write(uint8_t pin, uint8_t value)=0
bool force_safety_on(void) override
void set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz, uint32_t &rate_mask)
enum output_mode _output_mode
virtual void printf(const char *,...) FMT_PRINTF(2
uint16_t _last_safety_options
void force_safety_pending_requests(void)
unsigned _alt_servo_count
uint32_t _last_safety_options_check_ms
void force_safety_off(void) override
void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) override
uint16_t _period[PX4_NUM_OUTPUT_CHANNELS]
int close(int fileno)
POSIX Close a file with fileno handel.
struct PX4::PX4RCOutput::@107 _outputs[ORB_MULTI_MAX_INSTANCES]
volatile bool _need_update
uint16_t _default_rate_hz
virtual void pinMode(uint8_t pin, uint8_t output)=0
virtual enum safety_state safety_switch_state(void)
void set_default_rate(uint16_t rate_hz) override
uint16_t read(uint8_t ch) override
orb_advert_t _actuator_armed_pub
void _init_alt_channels(void)
actuator_outputs_s outputs
int stat(const char *name, struct stat *buf)
Display struct stat, from POSIX stat(0 or fstat(), in ASCII. NOT POSIX.
enum AP_HAL::Util::safety_state _safety_state_request
uint16_t _enabled_channels
void enable_ch(uint8_t ch) override
#define PX4_NUM_OUTPUT_CHANNELS
void panic(const char *errormsg,...) FMT_PRINTF(1
#define PWM_IGNORE_THIS_CHANNEL
uint16_t get_safety_button_options(void)
uint16_t get_freq(uint8_t ch) override
volatile uint8_t _max_channel
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override
void force_safety_no_wait(void) override