APM:Libraries
RCOutput_Disco.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 Andrew Tridgell. 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 
18 /*
19  RCOutput on the Disco combines I2C motor output (for channel 3) with
20  PWM output for the other channels. This class is a wrapper around
21  the two other classes
22  */
23 #include "RCOutput_Disco.h"
24 
25 #include <AP_Common/AP_Common.h>
26 #include <AP_HAL/AP_HAL.h>
27 #include <stdio.h>
28 
29 namespace Linux {
30 
32  : bebop_out(std::move(dev))
33 {
34 }
35 
37 {
38  sysfs_out.init();
39  bebop_out.init();
40  printf("RCOutput_Disco: initialised\n");
41 }
42 
43 void RCOutput_Disco::set_freq(uint32_t chmask, uint16_t freq_hz)
44 {
45  for (uint8_t i = 0; i < ARRAY_SIZE(output_table); i++) {
46  if (chmask & (1U << i)) {
47  output_table[i].output.set_freq(1U<<output_table[i].channel, freq_hz);
48  }
49  }
50 }
51 
52 uint16_t RCOutput_Disco::get_freq(uint8_t ch)
53 {
54  if (ch >= ARRAY_SIZE(output_table)) {
55  return 0;
56  }
57  return output_table[ch].output.get_freq(output_table[ch].channel);
58 }
59 
60 void RCOutput_Disco::enable_ch(uint8_t ch)
61 {
62  if (ch >= ARRAY_SIZE(output_table)) {
63  return;
64  }
65  output_table[ch].output.enable_ch(output_table[ch].channel);
66 }
67 
69 {
70  if (ch >= ARRAY_SIZE(output_table)) {
71  return;
72  }
73  output_table[ch].output.disable_ch(output_table[ch].channel);
74 }
75 
76 void RCOutput_Disco::write(uint8_t ch, uint16_t period_us)
77 {
78  if (ch >= ARRAY_SIZE(output_table)) {
79  return;
80  }
81  output_table[ch].output.write(output_table[ch].channel, period_us);
82 }
83 
84 uint16_t RCOutput_Disco::read(uint8_t ch)
85 {
86  if (ch >= ARRAY_SIZE(output_table)) {
87  return 0;
88  }
89  return output_table[ch].output.read(output_table[ch].channel);
90 }
91 
92 void RCOutput_Disco::read(uint16_t *period_us, uint8_t len)
93 {
94  for (int i = 0; i < len; i++) {
95  period_us[i] = read(i);
96  }
97 }
98 
100 {
101  sysfs_out.cork();
102  bebop_out.cork();
103 }
104 
106 {
107  sysfs_out.push();
108  bebop_out.push();
109 }
110 
111 void RCOutput_Disco::set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
112 {
113  sysfs_out.set_esc_scaling(min_pwm, max_pwm);
114  bebop_out.set_esc_scaling(min_pwm, max_pwm);
115 }
116 
117 }
int printf(const char *fmt,...)
Definition: stdio.c:113
void cork(void) override
uint16_t get_freq(uint8_t ch) override
const output_table_t output_table[7]
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override
virtual void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
Definition: RCOutput.h:111
void write(uint8_t ch, uint16_t period_us) override
RCOutput_Disco(AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override
uint16_t read(uint8_t ch) override
void set_freq(uint32_t chmask, uint16_t freq_hz) override
void enable_ch(uint8_t ch) override
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
void init() override
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
void push(void) override
Common definitions and utility routines for the ArduPilot libraries.
RCOutput_Sysfs sysfs_out
RCOutput_Bebop bebop_out
void disable_ch(uint8_t ch) override
void cork() override