2017-02-07 23:26:09 -04:00
|
|
|
/*
|
|
|
|
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
|
|
|
* Copyright (C) 2017 Intel Corporation. All rights reserved.
|
|
|
|
*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
/*
|
|
|
|
* Implementation of TAP UART ESCs. Used the implementation from PX4 as a base
|
|
|
|
* which is BSD-licensed:
|
|
|
|
*
|
|
|
|
* Redistribution and use in source and binary forms, with or without
|
|
|
|
* modification, are permitted provided that the following conditions
|
|
|
|
* are met:
|
|
|
|
*
|
|
|
|
* 1. Redistributions of source code must retain the above copyright
|
|
|
|
* notice, this list of conditions and the following disclaimer.
|
|
|
|
* 2. Redistributions in binary form must reproduce the above copyright
|
|
|
|
* notice, this list of conditions and the following disclaimer in
|
|
|
|
* the documentation and/or other materials provided with the
|
|
|
|
* distribution.
|
|
|
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
|
|
* used to endorse or promote products derived from this software
|
|
|
|
* without specific prior written permission.
|
|
|
|
*
|
|
|
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
|
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
|
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
|
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
|
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
|
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
|
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
|
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
|
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
|
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
|
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
|
|
* POSSIBILITY OF SUCH DAMAGE.
|
|
|
|
*/
|
2017-02-07 04:43:51 -04:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "AP_HAL_PX4.h"
|
|
|
|
#include <systemlib/perf_counter.h>
|
|
|
|
#include <uORB/topics/actuator_armed.h>
|
|
|
|
|
|
|
|
namespace PX4 {
|
|
|
|
|
2017-02-07 23:26:09 -04:00
|
|
|
struct EscPacket;
|
|
|
|
|
2017-02-07 04:43:51 -04:00
|
|
|
class RCOutput_Tap : public AP_HAL::RCOutput {
|
|
|
|
public:
|
|
|
|
void init() override;
|
|
|
|
void set_freq(uint32_t chmask, uint16_t freq_hz) override;
|
|
|
|
uint16_t get_freq(uint8_t ch) override;
|
|
|
|
void enable_ch(uint8_t ch) override;
|
|
|
|
void disable_ch(uint8_t ch) override;
|
|
|
|
void write(uint8_t ch, uint16_t period_us) override;
|
|
|
|
uint16_t read(uint8_t ch) override;
|
|
|
|
void read(uint16_t *period_us, uint8_t len) override;
|
|
|
|
|
|
|
|
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override {
|
|
|
|
_esc_pwm_min = min_pwm;
|
|
|
|
_esc_pwm_max = max_pwm;
|
|
|
|
}
|
|
|
|
|
|
|
|
void cork() override;
|
|
|
|
void push() override;
|
|
|
|
|
|
|
|
private:
|
2017-02-07 23:26:09 -04:00
|
|
|
static uint8_t _crc8_esc(uint8_t *p, uint8_t len);
|
|
|
|
static uint8_t _crc_packet(EscPacket &p);
|
|
|
|
|
2017-02-07 04:43:51 -04:00
|
|
|
static const uint8_t MAX_MOTORS = 4;
|
|
|
|
|
2017-02-07 23:26:09 -04:00
|
|
|
int _send_packet(EscPacket &p);
|
|
|
|
bool _uart_open();
|
|
|
|
void _uart_close();
|
2017-02-07 04:43:51 -04:00
|
|
|
|
2017-02-07 23:26:09 -04:00
|
|
|
perf_counter_t _perf_rcout;
|
|
|
|
|
|
|
|
uint8_t _enabled_channels;
|
|
|
|
bool _corking;
|
|
|
|
|
|
|
|
uint8_t _channels_count = MAX_MOTORS;
|
|
|
|
uint8_t _next_channel_reply;
|
2017-02-07 04:43:51 -04:00
|
|
|
|
|
|
|
uint16_t _period[MAX_MOTORS];
|
2017-02-07 23:26:09 -04:00
|
|
|
uint16_t _esc_pwm_min;
|
|
|
|
uint16_t _esc_pwm_max;
|
|
|
|
int _uart_fd = -1;
|
2017-02-07 04:43:51 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
}
|