Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_FETtecOneWire/AP_FETtecOneWire.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415/* Initial protocol implementation was provided by FETtec */16/* Strongly modified by Amilcar Lucas, IAV GmbH */1718#pragma once1920#include <AP_HAL/AP_HAL.h>2122#ifndef AP_FETTEC_ONEWIRE_ENABLED23#define AP_FETTEC_ONEWIRE_ENABLED BOARD_FLASH_SIZE > 102424#endif2526// Support both full-duplex at 500Kbit/s as well as half-duplex at 2Mbit/s (optional feature)27#ifndef HAL_AP_FETTEC_HALF_DUPLEX28#define HAL_AP_FETTEC_HALF_DUPLEX 029#endif3031// Get static info from the ESCs (optional feature)32#ifndef HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO33#define HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO 034#endif3536// provide beep support (optional feature)37#ifndef HAL_AP_FETTEC_ESC_BEEP38#define HAL_AP_FETTEC_ESC_BEEP 039#endif4041// provide light support (optional feature)42#ifndef HAL_AP_FETTEC_ESC_LIGHT43#define HAL_AP_FETTEC_ESC_LIGHT 044#endif4546#if AP_FETTEC_ONEWIRE_ENABLED4748#define FTW_DEBUGGING 049#if FTW_DEBUGGING50#include <stdio.h>51#define fet_debug(fmt, args ...) do {::fprintf(stderr,"FETtec: %s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)52#else53#define fet_debug(fmt, args ...)54#endif5556#include <AP_ESC_Telem/AP_ESC_Telem.h>57#include <AP_Param/AP_Param.h>5859#include <AP_Math/AP_Math.h>60#include <AP_Math/crc.h>6162class AP_FETtecOneWire : public AP_ESC_Telem_Backend63{6465public:66AP_FETtecOneWire();6768/// Do not allow copies69CLASS_NO_COPY(AP_FETtecOneWire);7071static const struct AP_Param::GroupInfo var_info[];7273static AP_FETtecOneWire *get_singleton() {74return _singleton;75}7677/// periodically called from SRV_Channels::push()78void update();7980/// called from AP_Arming; should return false if arming should be81/// disallowed82bool pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const;8384#if HAL_AP_FETTEC_ESC_BEEP85/**86makes all connected ESCs beep87@param beep_frequency a 8 bit value from 0-255. higher make a higher beep88*/89void beep(const uint8_t beep_frequency);90#endif9192#if HAL_AP_FETTEC_ESC_LIGHT93/**94sets the racewire color for all ESCs95@param r red brightness96@param g green brightness97@param b blue brightness98*/99void led_color(const uint8_t r, const uint8_t g, const uint8_t b);100#endif101102private:103static AP_FETtecOneWire *_singleton;104AP_HAL::UARTDriver *_uart;105106AP_Int32 _motor_mask_parameter;107AP_Int32 _reverse_mask_parameter;108#if HAL_WITH_ESC_TELEM109AP_Int8 _pole_count_parameter;110#endif111112static constexpr uint8_t FRAME_OVERHEAD = 6; ///< OneWire message frame overhead (header+tail bytes)113static constexpr uint8_t MAX_RECEIVE_LENGTH = 12; ///< OneWire max receive message payload length in bytes114#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO115static constexpr uint8_t SERIAL_NUMBER_LENGTH = 12; ///< ESC serial number length in bytes116#endif117118/**119initialize the device driver: configure serial port, wake-up and configure ESCs120*/121void init();122123/**124initialize the serial port125*/126void init_uart();127128/**129scan the OneWire bus, configure the ESCs requested in the _motor_mask_parameter130*/131void configure_escs();132133// states configured ESCs can be in:134enum class ESCState : uint8_t {135UNINITIALISED = 5, // when we haven't tried to send anything to the ESC136137WANT_SEND_OK_TO_GET_RUNNING_SW_TYPE = 10,138WAITING_OK_FOR_RUNNING_SW_TYPE = 11,139140WANT_SEND_START_FW = 20,141WAITING_OK_FOR_START_FW = 21,142143#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO144WANT_SEND_REQ_TYPE = 30,145WAITING_ESC_TYPE = 31,146147WANT_SEND_REQ_SW_VER = 40,148WAITING_SW_VER = 41,149150WANT_SEND_REQ_SN = 50,151WAITING_SN = 51,152#endif153154#if HAL_WITH_ESC_TELEM155WANT_SEND_SET_TLM_TYPE = 60,156WAITING_SET_TLM_TYPE_OK = 61,157#endif158159WANT_SEND_SET_FAST_COM_LENGTH = 70,160WAITING_SET_FAST_COM_LENGTH_OK = 71,161162RUNNING = 100,163};164165class ESC {166public:167168#if HAL_WITH_ESC_TELEM169uint32_t last_telem_us; ///< last time we got telemetry from this ESC170uint16_t unexpected_telem;171uint16_t error_count_at_throttle_count_overflow; ///< overflow counter for error counter from the ESCs.172bool telem_expected; ///< this ESC is fully configured and is now expected to send us telemetry173bool telem_requested; ///< this ESC is fully configured and at some point was requested to send us telemetry174#endif175176uint8_t id; ///< FETtec ESC ID177uint8_t servo_ofs; ///< offset into ArduPilot servo array178bool is_awake;179void set_state(ESCState _state) {180fet_debug("Moving ESC.id=%u from state=%u to state=%u", (unsigned)id, (unsigned)state, (unsigned)_state);181state = _state;182};183ESCState state = ESCState::UNINITIALISED;184185#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO186uint8_t serial_number[SERIAL_NUMBER_LENGTH];187uint8_t firmware_version;188uint8_t firmware_subversion;189uint8_t type;190#endif191};192193uint32_t _min_fast_throttle_period_us; ///< minimum allowed fast-throttle command transmit period194uint32_t _motor_mask; ///< an un-mutable copy of the _motor_mask_parameter taken before _init_done goes true195uint32_t _reverse_mask; ///< a copy of the _reverse_mask_parameter taken while not armed196uint32_t _running_mask; ///< a bitmask of the actively running ESCs197uint32_t _last_transmit_us; ///< last time the transmit() function sent data198ESC *_escs;199uint8_t _esc_count; ///< number of allocated ESCs200uint8_t _fast_throttle_byte_count; ///< pre-calculated number of bytes required to send an entire packed throttle message201202#if HAL_AP_FETTEC_HALF_DUPLEX203uint8_t _ignore_own_bytes; ///< bytes to ignore while receiving, because we have transmitted them ourselves204uint8_t _last_crc; ///< the CRC from the last sent fast-throttle command205bool _use_hdplex; ///< use asynchronous half-duplex serial communication206#endif207208bool _init_done; ///< device driver is initialized; ESCs may still need to be configured209bool _invalid_mask; ///< true if the mask parameter is invalid210211enum class FrameSource : uint8_t {212MASTER = 0x01, ///< master is always 0x01213BOOTLOADER = 0x02,214ESC = 0x03,215};216217enum class MsgType : uint8_t218{219OK = 0,220BL_PAGE_CORRECT = 1, ///< Bootloader only221NOT_OK = 2,222BL_START_FW = 3, ///< Bootloader only - exit the boot loader and start the standard firmware223BL_PAGES_TO_FLASH = 4, ///< Bootloader only224#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO225REQ_TYPE = 5, ///< ESC type226REQ_SN = 6, ///< serial number227REQ_SW_VER = 7, ///< software version228#endif229#if HAL_AP_FETTEC_ESC_BEEP230BEEP = 13, ///< make noise231#endif232SET_FAST_COM_LENGTH = 26, ///< configure fast-throttle command233SET_TLM_TYPE = 27, ///< telemetry operation mode234#if HAL_AP_FETTEC_ESC_LIGHT235SET_LED_TMP_COLOR = 51, ///< set ESC's LED color236#endif237};238239/**240a frame looks like:241byte 1 = frame header (master is always 0x01)242byte 2 = target ID (5bit)243byte 3 & 4 = frame type (always 0x00, 0x00 used for bootloader. here just for compatibility)244byte 5 = frame length over all bytes245byte 6 - X = request type, followed by the payload246byte X+1 = 8bit CRC247*/248template <typename T>249class PACKED PackedMessage {250public:251PackedMessage(uint8_t _esc_id, T _msg) :252esc_id(_esc_id),253msg(_msg)254{255update_checksum();256}257uint8_t frame_source { (uint8_t)FrameSource::MASTER };258uint8_t esc_id;259uint16_t frame_type { 0 }; // bootloader only, always zero260uint8_t frame_length {sizeof(T) + FRAME_OVERHEAD}; // all bytes including frame_source and checksum261T msg;262uint8_t checksum;263264void update_checksum() {265checksum = crc8_dvb_update(0, (const uint8_t*)this, frame_length-1);266}267};268269class PACKED OK {270public:271uint8_t msgid { (uint8_t)MsgType::OK };272};273274class PACKED START_FW {275public:276uint8_t msgid { (uint8_t)MsgType::BL_START_FW };277};278279class PACKED SET_FAST_COM_LENGTH {280public:281SET_FAST_COM_LENGTH(uint8_t _byte_count, uint8_t _min_esc_id, uint8_t _esc_count) :282byte_count{_byte_count},283min_esc_id{_min_esc_id},284esc_count{_esc_count}285{ }286uint8_t msgid { (uint8_t)MsgType::SET_FAST_COM_LENGTH };287uint8_t byte_count;288uint8_t min_esc_id;289uint8_t esc_count;290};291292#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO293class PACKED REQ_TYPE {294public:295uint8_t msgid { (uint8_t)MsgType::REQ_TYPE };296};297298class PACKED REQ_SW_VER {299public:300uint8_t msgid { (uint8_t)MsgType::REQ_SW_VER };301};302303class PACKED REQ_SN {304public:305uint8_t msgid { (uint8_t)MsgType::REQ_SN };306};307308class PACKED ESC_TYPE {309public:310ESC_TYPE(uint8_t _type) :311type{_type} { }312uint8_t type;313};314315class PACKED SW_VER {316public:317SW_VER(uint8_t _version, uint8_t _subversion) :318version{_version},319subversion{_subversion}320{ }321uint8_t version;322uint8_t subversion;323};324325class PACKED SN {326public:327SN(uint8_t *_sn, uint8_t snlen) {328memcpy(sn, _sn, ARRAY_SIZE(sn));329}330uint8_t sn[SERIAL_NUMBER_LENGTH];331};332333#endif // HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO334335void pack_fast_throttle_command(const uint16_t *motor_values, uint8_t *buffer, const uint8_t length, const uint8_t esc_id_to_request_telem_from);336337/*338* Messages, methods and states for dealing with ESC telemetry339*/340#if HAL_WITH_ESC_TELEM341void handle_message_telem(ESC &esc);342343uint16_t _fast_throttle_cmd_count; ///< number of fast-throttle commands sent by the flight controller344345/// the ESC at this offset into _escs should be the next to send a346/// telemetry request for:347uint8_t _esc_ofs_to_request_telem_from;348349class PACKED SET_TLM_TYPE {350public:351SET_TLM_TYPE(uint8_t _tlm_type) :352tlm_type{_tlm_type}353{ }354uint8_t msgid { (uint8_t)MsgType::SET_TLM_TYPE };355uint8_t tlm_type;356};357358class PACKED TLM {359public:360TLM(int8_t _temp, uint16_t _voltage, uint16_t _current, int16_t _rpm, uint16_t _consumption_mah, uint16_t _tx_err_count) :361temp{_temp},362voltage{_voltage},363current{_current},364rpm{_rpm},365consumption_mah{_consumption_mah},366tx_err_count{_tx_err_count}367{ }368int8_t temp; // centi-degrees369uint16_t voltage; // centi-Volt370uint16_t current; // centi-Ampere (signed?)371int16_t rpm; // centi-rpm372uint16_t consumption_mah; // milli-Ampere.hour373uint16_t tx_err_count; // CRC error count, as perceived from the ESC receiving side374};375376#endif // HAL_WITH_ESC_TELEM377378#if HAL_AP_FETTEC_ESC_BEEP379class PACKED Beep {380public:381Beep(uint8_t _beep_frequency) :382beep_frequency{_beep_frequency}383{ }384uint8_t msgid { (uint8_t)MsgType::BEEP };385uint8_t beep_frequency;386// add two zeros to make sure all ESCs can catch their command as we don't wait for a response here (don't blame me --pb)387uint16_t spacer = 0;388};389#endif // HAL_AP_FETTEC_ESC_BEEP390391#if HAL_AP_FETTEC_ESC_LIGHT392class PACKED LEDColour {393public:394LEDColour(uint8_t _r, uint8_t _g, uint8_t _b) :395r{_r},396g{_g},397b{_b}398{ }399uint8_t msgid { (uint8_t)MsgType::SET_LED_TMP_COLOR };400uint8_t r;401uint8_t g;402uint8_t b;403// add two zeros to make sure all ESCs can catch their command as we don't wait for a response here (don't blame me --pb)404uint16_t spacer = 0;405};406#endif // HAL_AP_FETTEC_ESC_LIGHT407408/*409* Methods and data for transmitting data to the ESCSs:410*/411412/**413transmits data to ESCs414@param bytes bytes to transmit415@param length number of bytes to transmit416@return false there's no space in the UART for this message417*/418bool transmit(const uint8_t* bytes, const uint8_t length);419420template <typename T>421bool transmit(const PackedMessage<T> &msg) {422return transmit((const uint8_t*)&msg, sizeof(msg));423}424425/**426transmits configuration request data to ESCs427@param bytes bytes to transmit428@param length number of bytes to transmit429@return false if vehicle armed or there's no space in the UART for this message430*/431bool transmit_config_request(const uint8_t* bytes, const uint8_t length);432433template <typename T>434bool transmit_config_request(const PackedMessage<T> &msg) {435return transmit_config_request((const uint8_t*)&msg, sizeof(msg));436}437438/**439sends a single fast-throttle frame containing the throttle for all configured OneWire ESCs.440@param motor_values a 16bit array containing the throttle values that should be sent to the motors. 0-2000 where 1001-2000 is positive rotation and 999-0 reversed rotation441*/442void escs_set_values(const uint16_t *motor_values);443444/*445* Methods and data for receiving data from the ESCs:446*/447448// FIXME: this should be tighter - and probably calculated. Note449// that we can't request telemetry faster than the loop interval,450// which is 20ms on Plane, so that puts a constraint here. When451// using fast-throttle with 12 ESCs on Plane you could expect452// 240ms between telem updates. Why you have a Plane with 12 ESCs453// is a bit of a puzzle.454static const uint32_t max_telem_interval_us = 100000;455456void handle_message(ESC &esc, const uint8_t length);457458/**459reads data from the UART, calling handle_message on any message found460*/461void read_data_from_uart();462union MessageUnion {463MessageUnion() { }464PackedMessage<OK> packed_ok;465#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO466PackedMessage<ESC_TYPE> packed_esc_type;467PackedMessage<SW_VER> packed_sw_ver;468PackedMessage<SN> packed_sn;469#endif470#if HAL_WITH_ESC_TELEM471PackedMessage<TLM> packed_tlm;472#endif473uint8_t receive_buf[FRAME_OVERHEAD + MAX_RECEIVE_LENGTH];474} u;475476static_assert(sizeof(u.packed_ok) <= sizeof(u.receive_buf),"packed_ok does not fit in receive_buf. MAX_RECEIVE_LENGTH too small?");477#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO478static_assert(sizeof(u.packed_esc_type) <= sizeof(u.receive_buf),"packed_esc_type does not fit in receive_buf. MAX_RECEIVE_LENGTH too small?");479static_assert(sizeof(u.packed_sw_ver) <= sizeof(u.receive_buf),"packed_sw_ver does not fit in receive_buf. MAX_RECEIVE_LENGTH too small?");480static_assert(sizeof(u.packed_sn) <= sizeof(u.receive_buf),"packed_sn does not fit in receive_buf. MAX_RECEIVE_LENGTH too small?");481#endif482#if HAL_WITH_ESC_TELEM483static_assert(sizeof(u.packed_tlm) <= sizeof(u.receive_buf),"packed_tlm does not fit in receive_buf. MAX_RECEIVE_LENGTH too small?");484#endif485486uint16_t _unknown_esc_message;487uint16_t _message_invalid_in_state_count;488uint16_t _period_too_short;489uint16_t crc_rec_err_cnt;490uint8_t _receive_buf_used;491492/// shifts data to start of buffer based on magic header bytes493void move_frame_source_in_receive_buffer(const uint8_t search_start_pos = 0);494495/// cut n bytes from start of buffer496void consume_bytes(const uint8_t n);497498/// returns true if the first message in the buffer is OK499bool buffer_contains_ok(const uint8_t length);500};501#endif // AP_FETTEC_ONEWIRE_ENABLED502503504