3 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 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);
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);
142 if (freq_hz > 50 || freq_hz == 1) {
144 rate_mask |= chmask & 0xFFF;
145 #if defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52) 146 if (rate_mask & 0x0F) {
149 if (rate_mask & 0x30) {
152 if (rate_mask & 0xC0) {
155 if (rate_mask & 0x700) {
159 if (rate_mask & 0x07) {
162 if (rate_mask & 0x38) {
165 if (rate_mask & 0xC0) {
168 if (rate_mask & 0xF00) {
174 #if defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52) 184 if (chmask & 0x700) {
197 if (chmask & 0xF00) {
203 if (ioctl(fd, PWM_SERVO_SET_SELECT_UPDATE_RATE, rate_mask) != 0) {
204 hal.
console->
printf(
"RCOutput: Unable to set alt rate mask to 0x%x\n", (
unsigned)rate_mask);
208 ioctl(fd, PWM_SERVO_SET_UPDATE_CLOCK, 8);
224 hal.
console->
printf(
"RCOutput: Unable to get servo count\n");
233 uint32_t primary_mask = chmask & ((1UL<<
_servo_count)-1);
235 if (primary_mask &&
_pwm_fd != -1) {
238 if (alt_mask &&
_alt_fd != -1) {
287 struct pwm_output_values pwm_values;
288 memset(&pwm_values, 0,
sizeof(pwm_values));
290 if ((1UL<<i) & chmask) {
291 pwm_values.values[i] = period_us;
293 pwm_values.channel_count++;
295 int ret = ioctl(
_pwm_fd, PWM_SERVO_SET_DISARMED_PWM, (
long unsigned int)&pwm_values);
297 hal.
console->
printf(
"Failed to setup disarmed PWM for 0x%08x to %u\n", (
unsigned)chmask, period_us);
303 struct pwm_output_values pwm_values;
304 memset(&pwm_values, 0,
sizeof(pwm_values));
306 if ((1UL<<i) & chmask) {
307 pwm_values.values[i] = period_us;
309 pwm_values.channel_count++;
311 int ret = ioctl(
_pwm_fd, PWM_SERVO_SET_FAILSAFE_PWM, (
long unsigned int)&pwm_values);
313 hal.
console->
printf(
"Failed to setup failsafe PWM for 0x%08x to %u\n", (
unsigned)chmask, period_us);
341 ioctl(
_pwm_fd, PWM_SERVO_SET_FORCE_SAFETY_ON, 0);
345 ioctl(
_pwm_fd, PWM_SERVO_SET_FORCE_SAFETY_OFF, 0);
401 if (period_us !=
_period[ch] ||
418 for (uint8_t i=0; i<ORB_MULTI_MAX_INSTANCES; i++) {
421 _outputs[i].outputs.output[ch] > 0) {
422 return _outputs[i].outputs.output[ch];
430 for (uint8_t i=0; i<len; i++) {
431 period_us[i] =
read(i);
446 for (uint8_t i=0; i<len; i++) {
456 if (
_armed.armed == arm) {
461 _armed.timestamp = hrt_absolute_time();
466 _armed.ready_to_arm =
true;
469 _armed.force_failsafe =
false;
513 for (
int i=to_send-1; i >= 0; i--) {
544 for (uint8_t i=0; i<ORB_MULTI_MAX_INSTANCES; i++) {
545 bool rc_updated =
false;
557 #if RCOUT_DEBUG_LATENCY 566 #if RCOUT_DEBUG_LATENCY 595 int fd =
open(
"/dev/px4io", 0);
599 for (uint8_t tries=0; tries<10; tries++) {
600 if (ioctl(fd, SBUS_SET_PROTO_VERSION, 1) != 0) {
603 if (ioctl(fd, PWM_SERVO_SET_SBUS_RATE, rate_hz) != 0) {
639 ioctl(
_pwm_fd, PWM_SERVO_SET_ONESHOT, 1);
641 ioctl(
_alt_fd, PWM_SERVO_SET_ONESHOT, 1);
652 ioctl(
_pwm_fd, PWM_SERVO_SET_ONESHOT, 0);
654 ioctl(
_alt_fd, PWM_SERVO_SET_ONESHOT, 0);
659 ioctl(
_pwm_fd, PWM_SERVO_SET_UPDATE_CLOCK, 8);
661 ioctl(
_alt_fd, PWM_SERVO_SET_UPDATE_CLOCK, 8);
673 ioctl(
_pwm_fd, PWM_SERVO_SET_DEFAULT_UPDATE_RATE, rate_hz);
676 ioctl(
_alt_fd, PWM_SERVO_SET_DEFAULT_UPDATE_RATE, rate_hz);
682 #endif // CONFIG_HAL_BOARD void timer_tick(void) override
perf_counter_t _perf_rcout
uint16_t get_freq(uint8_t ch) override
enum AP_HAL::Util::safety_state _safety_state_request
void disable_ch(uint8_t ch) override
uint32_t _safety_state_request_last_ms
volatile bool _need_update
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
void set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz, uint32_t &rate_mask)
unsigned _alt_servo_count
AP_HAL::UARTDriver * console
uint16_t read_last_sent(uint8_t ch) override
struct VRBRAIN::VRBRAINRCOutput::@116 _outputs[ORB_MULTI_MAX_INSTANCES]
void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) override
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override
bool enable_px4io_sbus_out(uint16_t rate_hz) override
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
volatile uint8_t _max_channel
virtual void write(uint8_t pin, uint8_t value)=0
orb_advert_t _actuator_armed_pub
void force_safety_off(void) override
virtual void printf(const char *,...) FMT_PRINTF(2
enum output_mode _output_mode
uint16_t _enabled_channels
#define VRBRAIN_NUM_OUTPUT_CHANNELS
void set_freq(uint32_t chmask, uint16_t freq_hz) override
int close(int fileno)
POSIX Close a file with fileno handel.
virtual void pinMode(uint8_t pin, uint8_t output)=0
virtual enum safety_state safety_switch_state(void)
void write(uint8_t ch, uint16_t period_us) override
void force_safety_no_wait(void) override
void _arm_actuators(bool arm)
actuator_outputs_s outputs
uint16_t _period[VRBRAIN_NUM_OUTPUT_CHANNELS]
void enable_ch(uint8_t ch) override
uint16_t _last_sent[VRBRAIN_NUM_OUTPUT_CHANNELS]
void set_output_mode(uint16_t mask, enum output_mode mode) override
uint16_t read(uint8_t ch) override
void force_safety_pending_requests(void)
void panic(const char *errormsg,...) FMT_PRINTF(1
#define PWM_IGNORE_THIS_CHANNEL
void _init_alt_channels(void)
void set_default_rate(uint16_t rate_hz) override
uint16_t _default_rate_hz
bool force_safety_on(void) override