2020-05-31 08:43:28 -03:00
|
|
|
/*
|
|
|
|
* 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/>.
|
|
|
|
*
|
|
|
|
* Code by Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
2023-03-10 20:46:34 -04:00
|
|
|
#include "AP_CANManager_config.h"
|
|
|
|
|
2023-04-18 05:06:53 -03:00
|
|
|
#if HAL_CANMANAGER_ENABLED
|
2020-05-31 08:43:28 -03:00
|
|
|
|
2023-04-18 05:06:53 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2020-05-31 08:43:28 -03:00
|
|
|
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include "AP_SLCANIface.h"
|
|
|
|
#include "AP_CANDriver.h"
|
2022-11-08 00:23:09 -04:00
|
|
|
#include <GCS_MAVLink/GCS_config.h>
|
|
|
|
#if HAL_GCS_ENABLED
|
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
2022-11-28 00:36:26 -04:00
|
|
|
#include <AP_HAL/utility/RingBuffer.h>
|
2022-11-08 00:23:09 -04:00
|
|
|
#endif
|
2020-05-31 08:43:28 -03:00
|
|
|
|
2023-04-18 04:24:17 -03:00
|
|
|
#include "AP_CAN.h"
|
|
|
|
|
2020-05-31 08:43:28 -03:00
|
|
|
class AP_CANManager
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
AP_CANManager();
|
|
|
|
|
|
|
|
/* Do not allow copies */
|
2022-09-30 06:50:43 -03:00
|
|
|
CLASS_NO_COPY(AP_CANManager);
|
2020-05-31 08:43:28 -03:00
|
|
|
|
|
|
|
static AP_CANManager* get_singleton()
|
|
|
|
{
|
2020-08-19 09:25:37 -03:00
|
|
|
if (_singleton == nullptr) {
|
|
|
|
AP_HAL::panic("CANManager used before allocation.");
|
|
|
|
}
|
2020-05-31 08:43:28 -03:00
|
|
|
return _singleton;
|
|
|
|
}
|
|
|
|
|
2020-11-29 19:46:55 -04:00
|
|
|
enum LogLevel : uint8_t {
|
2020-05-31 08:43:28 -03:00
|
|
|
LOG_NONE,
|
|
|
|
LOG_ERROR,
|
|
|
|
LOG_WARNING,
|
|
|
|
LOG_INFO,
|
|
|
|
LOG_DEBUG,
|
|
|
|
};
|
|
|
|
|
|
|
|
void init(void);
|
|
|
|
|
2020-12-31 19:45:53 -04:00
|
|
|
// register a new driver
|
2023-04-18 04:24:17 -03:00
|
|
|
bool register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver);
|
2020-12-31 19:45:53 -04:00
|
|
|
|
2020-05-31 08:43:28 -03:00
|
|
|
// returns number of active CAN Drivers
|
|
|
|
uint8_t get_num_drivers(void) const
|
|
|
|
{
|
2020-10-24 07:15:47 -03:00
|
|
|
return HAL_MAX_CAN_PROTOCOL_DRIVERS;
|
2020-05-31 08:43:28 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// return driver for index i
|
|
|
|
AP_CANDriver* get_driver(uint8_t i) const
|
|
|
|
{
|
|
|
|
if (i < HAL_NUM_CAN_IFACES) {
|
|
|
|
return _drivers[i];
|
|
|
|
}
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
2020-11-29 19:46:55 -04:00
|
|
|
// returns current log level
|
|
|
|
LogLevel get_log_level(void) const
|
|
|
|
{
|
|
|
|
return LogLevel(_loglevel.get());
|
|
|
|
}
|
|
|
|
|
2020-05-31 08:43:28 -03:00
|
|
|
// Method to log status and debug information for review while debugging
|
2021-08-03 23:44:30 -03:00
|
|
|
void log_text(AP_CANManager::LogLevel loglevel, const char *tag, const char *fmt, ...) FMT_PRINTF(4,5);
|
2020-05-31 08:43:28 -03:00
|
|
|
|
2020-12-30 02:23:26 -04:00
|
|
|
void log_retrieve(ExpandingString &str) const;
|
2020-05-31 08:43:28 -03:00
|
|
|
|
|
|
|
// return driver type index i
|
2023-04-18 04:24:17 -03:00
|
|
|
AP_CAN::Protocol get_driver_type(uint8_t i) const
|
2020-05-31 08:43:28 -03:00
|
|
|
{
|
|
|
|
if (i < HAL_NUM_CAN_IFACES) {
|
|
|
|
return _driver_type_cache[i];
|
|
|
|
}
|
2023-04-18 04:24:17 -03:00
|
|
|
return AP_CAN::Protocol::None;
|
2020-05-31 08:43:28 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
2022-02-06 17:22:53 -04:00
|
|
|
#if HAL_GCS_ENABLED
|
|
|
|
bool handle_can_forward(mavlink_channel_t chan, const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
2022-11-28 00:36:26 -04:00
|
|
|
void handle_can_frame(const mavlink_message_t &msg);
|
2022-02-14 02:29:32 -04:00
|
|
|
void handle_can_filter_modify(const mavlink_message_t &msg);
|
2022-02-06 17:22:53 -04:00
|
|
|
#endif
|
|
|
|
|
2020-05-31 08:43:28 -03:00
|
|
|
private:
|
|
|
|
|
|
|
|
// Parameter interface for CANIfaces
|
|
|
|
class CANIface_Params
|
|
|
|
{
|
|
|
|
friend class AP_CANManager;
|
|
|
|
|
|
|
|
public:
|
|
|
|
CANIface_Params()
|
|
|
|
{
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
}
|
|
|
|
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
private:
|
|
|
|
AP_Int8 _driver_number;
|
|
|
|
AP_Int32 _bitrate;
|
2022-02-10 03:39:27 -04:00
|
|
|
AP_Int32 _fdbitrate;
|
2020-05-31 08:43:28 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
//Parameter Interface for CANDrivers
|
|
|
|
class CANDriver_Params
|
|
|
|
{
|
|
|
|
friend class AP_CANManager;
|
|
|
|
|
|
|
|
public:
|
|
|
|
CANDriver_Params()
|
|
|
|
{
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
}
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
private:
|
|
|
|
AP_Int8 _driver_type;
|
|
|
|
AP_CANDriver* _uavcan;
|
2020-09-02 04:16:31 -03:00
|
|
|
AP_CANDriver* _piccolocan;
|
2020-05-31 08:43:28 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
CANIface_Params _interfaces[HAL_NUM_CAN_IFACES];
|
2020-12-31 19:45:53 -04:00
|
|
|
AP_CANDriver* _drivers[HAL_MAX_CAN_PROTOCOL_DRIVERS];
|
2020-05-31 08:43:28 -03:00
|
|
|
CANDriver_Params _drv_param[HAL_MAX_CAN_PROTOCOL_DRIVERS];
|
2023-04-18 04:24:17 -03:00
|
|
|
AP_CAN::Protocol _driver_type_cache[HAL_MAX_CAN_PROTOCOL_DRIVERS];
|
2020-05-31 08:43:28 -03:00
|
|
|
|
|
|
|
AP_Int8 _loglevel;
|
|
|
|
uint8_t _num_drivers;
|
2023-03-10 20:46:34 -04:00
|
|
|
#if AP_CAN_SLCAN_ENABLED
|
2020-05-31 08:43:28 -03:00
|
|
|
SLCAN::CANIface _slcan_interface;
|
2023-03-10 20:46:34 -04:00
|
|
|
#endif
|
|
|
|
|
2020-05-31 08:43:28 -03:00
|
|
|
static AP_CANManager *_singleton;
|
|
|
|
|
|
|
|
char* _log_buf;
|
|
|
|
uint32_t _log_pos;
|
2020-12-31 19:45:53 -04:00
|
|
|
|
|
|
|
HAL_Semaphore _sem;
|
2022-02-06 17:22:53 -04:00
|
|
|
|
|
|
|
#if HAL_GCS_ENABLED
|
|
|
|
/*
|
|
|
|
handler for CAN frames from the registered callback, sending frames
|
|
|
|
out as CAN_FRAME messages
|
|
|
|
*/
|
|
|
|
void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame);
|
|
|
|
|
|
|
|
struct {
|
|
|
|
mavlink_channel_t chan;
|
|
|
|
uint8_t system_id;
|
|
|
|
uint8_t component_id;
|
2022-02-13 18:08:42 -04:00
|
|
|
uint8_t frame_counter;
|
|
|
|
uint32_t last_callback_enable_ms;
|
|
|
|
HAL_Semaphore sem;
|
2022-02-14 02:29:32 -04:00
|
|
|
uint16_t num_filter_ids;
|
|
|
|
uint16_t *filter_ids;
|
2022-02-06 17:22:53 -04:00
|
|
|
} can_forward;
|
2022-11-28 00:36:26 -04:00
|
|
|
|
|
|
|
// buffer for MAVCAN frames
|
|
|
|
struct BufferFrame {
|
|
|
|
uint8_t bus;
|
|
|
|
AP_HAL::CANFrame frame;
|
|
|
|
};
|
|
|
|
ObjectBuffer<BufferFrame> *frame_buffer;
|
|
|
|
|
|
|
|
void process_frame_buffer(void);
|
2022-02-06 17:22:53 -04:00
|
|
|
#endif // HAL_GCS_ENABLED
|
2020-05-31 08:43:28 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
namespace AP
|
|
|
|
{
|
|
|
|
AP_CANManager& can();
|
|
|
|
}
|
|
|
|
|
2023-04-18 05:06:53 -03:00
|
|
|
#endif // HAL_CANMANAGER_ENABLED
|