APM:Libraries
RCOutput_Tap.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016 PX4 Development Team. All rights reserved.
3  * Copyright (C) 2017 Intel Corporation. All rights reserved.
4  *
5  * This file is free software: you can redistribute it and/or modify it
6  * under the terms of the GNU General Public License as published by the
7  * Free Software Foundation, either version 3 of the License, or
8  * (at your option) any later version.
9  *
10  * This file is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13  * See the GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License along
16  * with this program. If not, see <http://www.gnu.org/licenses/>.
17  */
18 
19 /*
20  * Implementation of TAP UART ESCs. Used the implementation from PX4 as a base
21  * which is BSD-licensed:
22  *
23  * Redistribution and use in source and binary forms, with or without
24  * modification, are permitted provided that the following conditions
25  * are met:
26  *
27  * 1. Redistributions of source code must retain the above copyright
28  * notice, this list of conditions and the following disclaimer.
29  * 2. Redistributions in binary form must reproduce the above copyright
30  * notice, this list of conditions and the following disclaimer in
31  * the documentation and/or other materials provided with the
32  * distribution.
33  * 3. Neither the name PX4 nor the names of its contributors may be
34  * used to endorse or promote products derived from this software
35  * without specific prior written permission.
36  *
37  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
38  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
39  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
40  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
41  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
42  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
43  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
44  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
45  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
46  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
47  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
48  * POSSIBILITY OF SUCH DAMAGE.
49  */
50 #pragma once
51 
52 #include <AP_HAL/Util.h>
53 
54 namespace ap {
55 
56 struct EscPacket;
57 
59 public:
60  void init() override;
61  void set_freq(uint32_t chmask, uint16_t freq_hz) override;
62  uint16_t get_freq(uint8_t ch) override;
63  void enable_ch(uint8_t ch) override;
64  void disable_ch(uint8_t ch) override;
65  void write(uint8_t ch, uint16_t period_us) override;
66  uint16_t read(uint8_t ch) override;
67  void read(uint16_t *period_us, uint8_t len) override;
68 
69  void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override {
70  _esc_pwm_min = min_pwm;
71  _esc_pwm_max = max_pwm;
72  }
73 
74  void cork() override;
75  void push() override;
76 
77 private:
78  static uint8_t _crc8_esc(uint8_t *p, uint8_t len);
79  static uint8_t _crc_packet(EscPacket &p);
80 
81  static const uint8_t MAX_MOTORS = 4;
82 
83  int _send_packet(EscPacket &p);
84  bool _uart_open();
85  bool _uart_set_speed(int speed);
86  void _uart_close();
87 
89 
91  bool _corking;
92  bool _led_on;
93 
95 
96  uint16_t _period[MAX_MOTORS];
97  uint16_t _esc_pwm_min;
98  uint16_t _esc_pwm_max;
100  int _uart_fd = -1;
101 };
102 
103 }
uint16_t _esc_pwm_max
Definition: RCOutput_Tap.h:98
static uint8_t _crc8_esc(uint8_t *p, uint8_t len)
bool _uart_set_speed(int speed)
uint8_t _enabled_channels
Definition: RCOutput_Tap.h:90
uint16_t read(uint8_t ch) override
void cork() override
void push() override
uint16_t _esc_pwm_min
Definition: RCOutput_Tap.h:97
void init() override
int _send_packet(EscPacket &p)
void set_freq(uint32_t chmask, uint16_t freq_hz) override
AP_HAL::Util::perf_counter_t _perf_rcout
Definition: RCOutput_Tap.h:88
void write(uint8_t ch, uint16_t period_us) override
void * perf_counter_t
Definition: Util.h:101
uint32_t _last_led_update_msec
Definition: RCOutput_Tap.h:99
static const uint8_t MAX_MOTORS
Definition: RCOutput_Tap.h:81
uint16_t get_freq(uint8_t ch) override
static uint8_t _crc_packet(EscPacket &p)
void disable_ch(uint8_t ch) override
uint16_t _period[MAX_MOTORS]
Definition: RCOutput_Tap.h:96
uint8_t _channels_count
Definition: RCOutput_Tap.h:94
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override
Definition: RCOutput_Tap.h:69
void enable_ch(uint8_t ch) override