2020-05-31 09:12:02 -03:00
|
|
|
/*
|
|
|
|
* Copyright (C) 2020 Siddharth B Purohit
|
|
|
|
*
|
|
|
|
* 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/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <stdint.h>
|
|
|
|
#include "AP_HAL_Namespace.h"
|
2021-05-17 14:35:29 -03:00
|
|
|
#include "AP_HAL_Boards.h"
|
2020-05-31 09:12:02 -03:00
|
|
|
|
2020-12-30 02:23:27 -04:00
|
|
|
class ExpandingString;
|
|
|
|
|
2020-05-31 09:12:02 -03:00
|
|
|
/**
|
|
|
|
* Raw CAN frame, as passed to/from the CAN driver.
|
|
|
|
*/
|
|
|
|
struct AP_HAL::CANFrame {
|
|
|
|
static const uint32_t MaskStdID = 0x000007FFU;
|
|
|
|
static const uint32_t MaskExtID = 0x1FFFFFFFU;
|
|
|
|
static const uint32_t FlagEFF = 1U << 31; ///< Extended frame format
|
|
|
|
static const uint32_t FlagRTR = 1U << 30; ///< Remote transmission request
|
|
|
|
static const uint32_t FlagERR = 1U << 29; ///< Error frame
|
|
|
|
|
2021-05-17 14:35:29 -03:00
|
|
|
#if HAL_CANFD_SUPPORTED
|
|
|
|
static const uint8_t NonFDCANMaxDataLen = 8;
|
2021-05-03 09:53:59 -03:00
|
|
|
static const uint8_t MaxDataLen = 64;
|
2021-05-17 14:35:29 -03:00
|
|
|
#else
|
|
|
|
static const uint8_t NonFDCANMaxDataLen = 8;
|
|
|
|
static const uint8_t MaxDataLen = 8;
|
|
|
|
#endif
|
2020-05-31 09:12:02 -03:00
|
|
|
uint32_t id; ///< CAN ID with flags (above)
|
2022-02-13 18:02:27 -04:00
|
|
|
union {
|
|
|
|
uint8_t data[MaxDataLen];
|
|
|
|
uint32_t data_32[MaxDataLen/4];
|
|
|
|
};
|
2020-05-31 09:12:02 -03:00
|
|
|
uint8_t dlc; ///< Data Length Code
|
2021-05-03 09:53:59 -03:00
|
|
|
bool canfd;
|
2020-05-31 09:12:02 -03:00
|
|
|
|
|
|
|
CANFrame() :
|
|
|
|
id(0),
|
2021-05-03 09:53:59 -03:00
|
|
|
dlc(0),
|
|
|
|
canfd(false)
|
2020-05-31 09:12:02 -03:00
|
|
|
{
|
|
|
|
memset(data,0, MaxDataLen);
|
|
|
|
}
|
|
|
|
|
2022-02-10 03:40:44 -04:00
|
|
|
CANFrame(uint32_t can_id, const uint8_t* can_data, uint8_t data_len, bool canfd_frame = false);
|
2020-05-31 09:12:02 -03:00
|
|
|
|
|
|
|
bool operator!=(const CANFrame& rhs) const
|
|
|
|
{
|
|
|
|
return !operator==(rhs);
|
|
|
|
}
|
|
|
|
bool operator==(const CANFrame& rhs) const
|
|
|
|
{
|
|
|
|
return (id == rhs.id) && (dlc == rhs.dlc) && (memcmp(data, rhs.data, dlc) == 0);
|
2022-09-29 21:44:59 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// signed version of id, for use by scriping where uint32_t is expensive
|
|
|
|
int32_t id_signed(void) const {
|
|
|
|
return isExtended()? int32_t(id & MaskExtID) : int32_t(id & MaskStdID);
|
2020-05-31 09:12:02 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
bool isExtended() const
|
|
|
|
{
|
|
|
|
return id & FlagEFF;
|
|
|
|
}
|
|
|
|
bool isRemoteTransmissionRequest() const
|
|
|
|
{
|
|
|
|
return id & FlagRTR;
|
|
|
|
}
|
|
|
|
bool isErrorFrame() const
|
|
|
|
{
|
|
|
|
return id & FlagERR;
|
|
|
|
}
|
2021-05-03 09:53:59 -03:00
|
|
|
void setCanFD(bool canfd_frame)
|
|
|
|
{
|
|
|
|
canfd = canfd_frame;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool isCanFDFrame() const
|
|
|
|
{
|
|
|
|
return canfd;
|
|
|
|
}
|
2020-05-31 09:12:02 -03:00
|
|
|
|
2022-02-10 03:40:44 -04:00
|
|
|
static uint8_t dlcToDataLength(uint8_t dlc);
|
2021-05-17 14:35:29 -03:00
|
|
|
|
2022-02-10 03:40:44 -04:00
|
|
|
static uint8_t dataLengthToDlc(uint8_t data_length);
|
2020-05-31 09:12:02 -03:00
|
|
|
/**
|
|
|
|
* CAN frame arbitration rules, particularly STD vs EXT:
|
|
|
|
* Marco Di Natale - "Understanding and using the Controller Area Network"
|
|
|
|
* http://www6.in.tum.de/pub/Main/TeachingWs2013MSE/CANbus.pdf
|
|
|
|
*/
|
|
|
|
bool priorityHigherThan(const CANFrame& rhs) const;
|
|
|
|
bool priorityLowerThan(const CANFrame& rhs) const
|
|
|
|
{
|
|
|
|
return rhs.priorityHigherThan(*this);
|
|
|
|
}
|
|
|
|
};
|
|
|
|
|
|
|
|
class AP_HAL::CANIface
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
|
|
|
|
enum OperatingMode {
|
|
|
|
PassThroughMode,
|
|
|
|
NormalMode,
|
2020-09-26 17:09:01 -03:00
|
|
|
SilentMode,
|
|
|
|
FilteredMode
|
2020-05-31 09:12:02 -03:00
|
|
|
};
|
|
|
|
|
2020-09-26 17:09:01 -03:00
|
|
|
OperatingMode get_operating_mode() { return mode_; }
|
|
|
|
|
2020-05-31 09:12:02 -03:00
|
|
|
typedef uint16_t CanIOFlags;
|
|
|
|
static const CanIOFlags Loopback = 1;
|
|
|
|
static const CanIOFlags AbortOnError = 2;
|
2022-02-06 17:22:53 -04:00
|
|
|
static const CanIOFlags IsMAVCAN = 4;
|
2020-05-31 09:12:02 -03:00
|
|
|
|
|
|
|
// Single Rx Frame with related info
|
|
|
|
struct CanRxItem {
|
|
|
|
uint64_t timestamp_us = 0;
|
|
|
|
CanIOFlags flags = 0;
|
|
|
|
CANFrame frame;
|
|
|
|
};
|
|
|
|
|
|
|
|
// Single Tx Frame with related info
|
|
|
|
struct CanTxItem {
|
|
|
|
uint64_t deadline = 0;
|
|
|
|
CANFrame frame;
|
|
|
|
uint32_t index = 0;
|
2020-08-23 17:05:40 -03:00
|
|
|
bool loopback:1;
|
|
|
|
bool abort_on_error:1;
|
|
|
|
bool aborted:1;
|
|
|
|
bool pushed:1;
|
|
|
|
bool setup:1;
|
2021-05-03 09:53:59 -03:00
|
|
|
bool canfd_frame:1;
|
2020-05-31 09:12:02 -03:00
|
|
|
|
|
|
|
bool operator<(const CanTxItem& rhs) const
|
|
|
|
{
|
|
|
|
if (frame.priorityLowerThan(rhs.frame)) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
if (frame.priorityHigherThan(rhs.frame)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return index > rhs.index;
|
|
|
|
}
|
|
|
|
};
|
|
|
|
|
|
|
|
struct CanFilterConfig {
|
|
|
|
uint32_t id = 0;
|
|
|
|
uint32_t mask = 0;
|
|
|
|
|
|
|
|
bool operator==(const CanFilterConfig& rhs) const
|
|
|
|
{
|
|
|
|
return rhs.id == id && rhs.mask == mask;
|
|
|
|
}
|
|
|
|
};
|
|
|
|
|
2022-02-10 03:40:05 -04:00
|
|
|
virtual bool init(const uint32_t bitrate, const uint32_t fdbitrate, const OperatingMode mode) {
|
2022-02-10 03:40:44 -04:00
|
|
|
return init(bitrate, mode);
|
|
|
|
}
|
|
|
|
|
2020-05-31 09:12:02 -03:00
|
|
|
// Initialise the interface with hardware configuration required to start comms.
|
|
|
|
virtual bool init(const uint32_t bitrate, const OperatingMode mode) = 0;
|
|
|
|
|
|
|
|
// Select method to notify user of Rx and Tx buffer state.
|
|
|
|
// fill read select with true if a frame is available in Rx buffer
|
|
|
|
// fill write select with true if space is available in Tx buffer
|
|
|
|
// Also waits for Rx or Tx event depending on read_select and write_select values
|
2023-10-11 04:41:53 -03:00
|
|
|
// passed to the method until timeout. Returns true if the Rx/Tx even occurred
|
2020-05-31 09:12:02 -03:00
|
|
|
// while waiting, false if timedout
|
|
|
|
virtual bool select(bool &read_select, bool &write_select,
|
|
|
|
const CANFrame* const pending_tx, uint64_t timeout)
|
|
|
|
{
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2023-12-29 17:29:46 -04:00
|
|
|
virtual bool set_event_handle(AP_HAL::BinarySemaphore *sem_handle)
|
2020-05-31 09:12:02 -03:00
|
|
|
{
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2023-10-11 04:41:53 -03:00
|
|
|
// Put frame in queue to be sent, return negative if error occurred, 0 if no space, and 1 if successful
|
2022-02-11 03:37:48 -04:00
|
|
|
// must be called on child class
|
2022-02-06 17:22:53 -04:00
|
|
|
virtual int16_t send(const CANFrame& frame, uint64_t tx_deadline, CanIOFlags flags);
|
2020-05-31 09:12:02 -03:00
|
|
|
|
2023-10-11 04:41:53 -03:00
|
|
|
// Non blocking receive frame that pops the frames received inside the buffer, return negative if error occurred,
|
2020-05-31 09:12:02 -03:00
|
|
|
// 0 if no frame available, 1 if successful
|
2022-02-11 03:37:48 -04:00
|
|
|
// must be called on child class
|
2022-02-06 17:22:53 -04:00
|
|
|
virtual int16_t receive(CANFrame& out_frame, uint64_t& out_ts_monotonic, CanIOFlags& out_flags);
|
2020-05-31 09:12:02 -03:00
|
|
|
|
|
|
|
//Configure filters so as to reject frames that are not going to be handled by us
|
|
|
|
virtual bool configureFilters(const CanFilterConfig* filter_configs, uint16_t num_configs)
|
|
|
|
{
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
//Number of available hardware filters.
|
|
|
|
virtual uint16_t getNumFilters() const
|
|
|
|
{
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
//Return Total Error Count generated so far
|
|
|
|
virtual uint32_t getErrorCount() const
|
|
|
|
{
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
2022-12-06 22:35:15 -04:00
|
|
|
typedef struct {
|
|
|
|
uint32_t tx_requests;
|
|
|
|
uint32_t tx_rejected;
|
|
|
|
uint32_t tx_overflow;
|
|
|
|
uint32_t tx_success;
|
|
|
|
uint32_t tx_timedout;
|
|
|
|
uint32_t tx_abort;
|
|
|
|
uint32_t rx_received;
|
|
|
|
uint32_t rx_overflow;
|
|
|
|
uint32_t rx_errors;
|
|
|
|
uint32_t num_busoff_err;
|
2023-09-01 01:42:23 -03:00
|
|
|
uint64_t last_transmit_us;
|
2022-12-06 22:35:15 -04:00
|
|
|
} bus_stats_t;
|
|
|
|
|
|
|
|
#if !defined(HAL_BOOTLOADER_BUILD)
|
2020-05-31 09:12:02 -03:00
|
|
|
//Get status info of the interface
|
2020-12-30 02:23:27 -04:00
|
|
|
virtual void get_stats(ExpandingString &str) {}
|
2020-05-31 09:12:02 -03:00
|
|
|
|
2022-12-06 22:35:15 -04:00
|
|
|
/*
|
|
|
|
return bus statistics for logging
|
|
|
|
return nullptr if no statistics available
|
|
|
|
*/
|
|
|
|
virtual const bus_stats_t *get_statistics(void) const { return nullptr; };
|
|
|
|
#endif
|
|
|
|
|
2020-05-31 09:12:02 -03:00
|
|
|
// return true if busoff was detected and not cleared
|
|
|
|
virtual bool is_busoff() const
|
|
|
|
{
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// Methods to be used only while testing CANBus
|
|
|
|
// Not for normal operation or use case
|
|
|
|
virtual void flush_tx() {}
|
|
|
|
virtual void clear_rx() {}
|
|
|
|
|
|
|
|
// return true if init was called and successful
|
|
|
|
virtual bool is_initialized() const = 0;
|
2022-02-06 17:22:53 -04:00
|
|
|
|
|
|
|
FUNCTOR_TYPEDEF(FrameCb, void, uint8_t, const AP_HAL::CANFrame &);
|
|
|
|
|
|
|
|
// register a frame callback function
|
2024-09-08 03:11:30 -03:00
|
|
|
virtual bool register_frame_callback(FrameCb cb, uint8_t &cb_id);
|
|
|
|
virtual void unregister_frame_callback(uint8_t cb_id);
|
2022-02-06 17:22:53 -04:00
|
|
|
|
2020-09-26 17:09:01 -03:00
|
|
|
protected:
|
2022-02-06 17:22:53 -04:00
|
|
|
virtual int8_t get_iface_num() const = 0;
|
|
|
|
virtual bool add_to_rx_queue(const CanRxItem &rx_item) = 0;
|
|
|
|
|
2024-09-08 03:11:30 -03:00
|
|
|
struct {
|
|
|
|
#ifndef HAL_BOOTLOADER_BUILD
|
|
|
|
HAL_Semaphore sem;
|
|
|
|
#endif
|
2024-11-29 23:57:37 -04:00
|
|
|
// allow up to 3 callbacks per interface
|
|
|
|
FrameCb cb[3];
|
2024-09-08 03:11:30 -03:00
|
|
|
} callbacks;
|
|
|
|
|
2020-09-26 17:09:01 -03:00
|
|
|
uint32_t bitrate_;
|
|
|
|
OperatingMode mode_;
|
2020-05-31 09:12:02 -03:00
|
|
|
};
|