APM:Libraries
RCOutput_Sysfs.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015 Intel Corporation. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #include "RCOutput_Sysfs.h"
18 
19 #include <AP_Common/AP_Common.h>
20 #include <AP_HAL/AP_HAL.h>
21 #include <AP_Math/AP_Math.h>
22 
23 namespace Linux {
24 
25 RCOutput_Sysfs::RCOutput_Sysfs(uint8_t chip, uint8_t channel_base, uint8_t channel_count)
26  : _chip(chip)
27  , _channel_base(channel_base)
28  , _channel_count(channel_count)
29  , _pwm_channels(new PWM_Sysfs_Base *[_channel_count])
30  , _pending(new uint16_t[_channel_count])
31 {
32 }
33 
35 {
36  for (uint8_t i = 0; i < _channel_count; i++) {
37  delete _pwm_channels[i];
38  }
39 
40  delete [] _pwm_channels;
41 }
42 
44 {
45  for (uint8_t i = 0; i < _channel_count; i++) {
46 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
48 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RST_ZYNQ
49  _pwm_channels[i] = new PWM_Sysfs(_chip+i, 0);
50 #else
52 #endif
53  if (!_pwm_channels[i]) {
54  AP_HAL::panic("RCOutput_Sysfs_PWM: Unable to setup PWM pin.");
55  }
56  _pwm_channels[i]->init();
57  _pwm_channels[i]->enable(false);
58 
59  /* Set the initial frequency */
60  _pwm_channels[i]->set_freq(50);
62  _pwm_channels[i]->set_polarity(PWM_Sysfs::Polarity::NORMAL);
63  }
64 }
65 
66 void RCOutput_Sysfs::set_freq(uint32_t chmask, uint16_t freq_hz)
67 {
68  for (uint8_t i = 0; i < _channel_count; i++) {
69  if (chmask & 1 << i) {
70  _pwm_channels[i]->set_freq(freq_hz);
71  }
72  }
73 }
74 
75 uint16_t RCOutput_Sysfs::get_freq(uint8_t ch)
76 {
77  if (ch >= _channel_count) {
78  return 0;
79  }
80 
81  return _pwm_channels[ch]->get_freq();
82 }
83 
84 void RCOutput_Sysfs::enable_ch(uint8_t ch)
85 {
86  if (ch >= _channel_count) {
87  return;
88  }
89 
90  _pwm_channels[ch]->enable(true);
91 }
92 
94 {
95  if (ch >= _channel_count) {
96  return;
97  }
98 
99  _pwm_channels[ch]->enable(false);
100 }
101 
102 void RCOutput_Sysfs::write(uint8_t ch, uint16_t period_us)
103 {
104  if (ch >= _channel_count) {
105  return;
106  }
107  if (_corked) {
108  _pending[ch] = period_us;
109  _pending_mask |= (1U<<ch);
110  } else {
111  _pwm_channels[ch]->set_duty_cycle(usec_to_nsec(period_us));
112  }
113 }
114 
115 uint16_t RCOutput_Sysfs::read(uint8_t ch)
116 {
117  if (ch >= _channel_count) {
118  return 1000;
119  }
120 
121  return nsec_to_usec(_pwm_channels[ch]->get_duty_cycle());
122 }
123 
124 void RCOutput_Sysfs::read(uint16_t *period_us, uint8_t len)
125 {
126  for (int i = 0; i < MIN(len, _channel_count); i++) {
127  period_us[i] = read(i);
128  }
129  for (int i = _channel_count; i < len; i++) {
130  period_us[i] = 1000;
131  }
132 }
133 
135 {
136  _corked = true;
137 }
138 
140 {
141  if (!_corked) {
142  return;
143  }
144  for (uint8_t i=0; i<_channel_count; i++) {
145  if ((1U<<i) & _pending_mask) {
147  }
148  }
149  _pending_mask = 0;
150  _corked = false;
151 }
152 
153 }
154 
const uint8_t _channel_base
void cork(void) override
void enable_ch(uint8_t ch)
RCOutput_Sysfs(uint8_t chip, uint8_t channel_base, uint8_t channel_count)
bool set_duty_cycle(uint32_t nsec_duty_cycle)
Definition: PWM_Sysfs.cpp:127
void set_freq(uint32_t chmask, uint16_t freq_hz)
uint16_t read(uint8_t ch)
uint32_t nsec_to_usec(uint32_t nsec)
Definition: AP_Math.h:222
const uint8_t _channel_count
PWM_Sysfs_Base ** _pwm_channels
#define MIN(a, b)
Definition: usb_conf.h:215
uint16_t get_freq(uint8_t ch)
uint32_t usec_to_nsec(uint32_t usec)
Definition: AP_Math.h:217
void push(void) override
virtual void set_polarity(PWM_Sysfs_Base::Polarity polarity)
Definition: PWM_Sysfs.cpp:143
Common definitions and utility routines for the ArduPilot libraries.
void disable_ch(uint8_t ch)
void write(uint8_t ch, uint16_t period_us)
void enable(bool value)
Definition: PWM_Sysfs.cpp:76
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
void set_freq(uint32_t freq)
Definition: PWM_Sysfs.cpp:117