2018-11-16 06:14:30 -04: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/>.
|
2019-01-23 00:09:44 -04:00
|
|
|
*
|
2018-11-16 06:14:30 -04:00
|
|
|
* Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "AP_HAL_ChibiOS.h"
|
|
|
|
|
2019-01-28 22:03:32 -04:00
|
|
|
#if HAL_WITH_UAVCAN && !HAL_MINIMIZE_FEATURES
|
2018-11-16 06:14:30 -04:00
|
|
|
#include "CAN.h"
|
|
|
|
#include <AP_UAVCAN/AP_UAVCAN_SLCAN.h>
|
|
|
|
|
|
|
|
#include "CANThread.h"
|
|
|
|
#include "CANClock.h"
|
|
|
|
#include "CANIface.h"
|
|
|
|
#define SLCAN_ROUTER_QUEUE_SIZE 64
|
|
|
|
|
|
|
|
struct CanRouteItem {
|
|
|
|
uint64_t utc_usec;
|
|
|
|
uavcan::CanFrame frame;
|
|
|
|
CanRouteItem() :
|
|
|
|
utc_usec(0)
|
|
|
|
{
|
|
|
|
}
|
|
|
|
};
|
|
|
|
|
2019-01-23 00:09:44 -04:00
|
|
|
class SLCANRouter {
|
2019-01-04 05:48:35 -04:00
|
|
|
ChibiOS_CAN::CanIface* _can_if;
|
|
|
|
SLCAN::CAN _slcan_if;
|
|
|
|
ObjectBuffer<CanRouteItem> _can_tx_queue;
|
|
|
|
ObjectBuffer<CanRouteItem> _slcan_tx_queue;
|
|
|
|
ChibiOS_CAN::BusEvent* _update_event;
|
|
|
|
uint32_t _last_active_time = 0;
|
|
|
|
uint32_t _slcan_rt_timeout = 0;
|
|
|
|
bool _thread_started = false;
|
|
|
|
bool _thread_suspended = false;
|
|
|
|
HAL_Semaphore router_sem;
|
|
|
|
thread_reference_t _s2c_thd_ref;
|
|
|
|
thread_reference_t _c2s_thd_ref;
|
|
|
|
void timer(void);
|
|
|
|
AP_HAL::UARTDriver* _port;
|
|
|
|
|
2018-11-16 06:14:30 -04:00
|
|
|
public:
|
2019-01-23 00:09:44 -04:00
|
|
|
SLCANRouter() : _slcan_if(SLCAN_DRIVER_INDEX, SLCAN_RX_QUEUE_SIZE), _can_tx_queue(SLCAN_ROUTER_QUEUE_SIZE), _slcan_tx_queue(SLCAN_ROUTER_QUEUE_SIZE)
|
2019-07-07 00:54:05 -03:00
|
|
|
{}
|
2018-11-16 06:14:30 -04:00
|
|
|
void init(ChibiOS_CAN::CanIface* can_if, ChibiOS_CAN::BusEvent* update_event);
|
|
|
|
void route_frame_to_slcan(ChibiOS_CAN::CanIface* can_if, const uavcan::CanFrame& frame, uint64_t timestamp_usec);
|
|
|
|
void route_frame_to_can(const uavcan::CanFrame& frame, uint64_t timestamp_usec);
|
|
|
|
void slcan2can_router_trampoline(void);
|
|
|
|
void can2slcan_router_trampoline(void);
|
2019-01-04 05:48:35 -04:00
|
|
|
void run(void);
|
2018-11-16 06:14:30 -04:00
|
|
|
|
2019-07-07 00:54:05 -03:00
|
|
|
};
|
2018-11-16 06:14:30 -04:00
|
|
|
|
|
|
|
#endif
|