CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_CANManager/AP_SLCANIface.h
Views: 1798
1
/*
2
* This file is free software: you can redistribute it and/or modify it
3
* under the terms of the GNU General Public License as published by the
4
* Free Software Foundation, either version 3 of the License, or
5
* (at your option) any later version.
6
*
7
* This file is distributed in the hope that it will be useful, but
8
* WITHOUT ANY WARRANTY; without even the implied warranty of
9
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10
* See the GNU General Public License for more details.
11
*
12
* You should have received a copy of the GNU General Public License along
13
* with this program. If not, see <http://www.gnu.org/licenses/>.
14
*
15
* Code by Siddharth Bharat Purohit
16
*/
17
18
#pragma once
19
20
#include "AP_CANManager_config.h"
21
22
#if AP_CAN_SLCAN_ENABLED
23
24
#include <AP_HAL/AP_HAL.h>
25
#include "AP_HAL/utility/RingBuffer.h"
26
#include <AP_Param/AP_Param.h>
27
28
#define SLCAN_BUFFER_SIZE 200
29
#define SLCAN_RX_QUEUE_SIZE 64
30
31
#ifndef HAL_CAN_RX_QUEUE_SIZE
32
#define HAL_CAN_RX_QUEUE_SIZE 128
33
#endif
34
35
static_assert(HAL_CAN_RX_QUEUE_SIZE <= 254, "Invalid CAN Rx queue size");
36
37
namespace SLCAN
38
{
39
40
class CANIface: public AP_HAL::CANIface
41
{
42
43
int16_t reportFrame(const AP_HAL::CANFrame& frame, uint64_t timestamp_usec);
44
45
const char* processCommand(char* cmd);
46
47
// pushes received frame into queue, false if failed
48
bool push_Frame(AP_HAL::CANFrame &frame);
49
50
// Methods to handle different types of frames,
51
// return true if successfully received frame type
52
bool handle_FrameRTRStd(const char* cmd);
53
bool handle_FrameRTRExt(const char* cmd);
54
bool handle_FrameDataStd(const char* cmd);
55
bool handle_FrameDataExt(const char* cmd, bool canfd);
56
57
bool handle_FDFrameDataExt(const char* cmd);
58
59
// Parsing bytes received on the serial port
60
inline void addByte(const uint8_t byte);
61
62
// track changes to slcan serial port
63
void update_slcan_port();
64
65
bool initialized_;
66
67
char buf_[SLCAN_BUFFER_SIZE + 1]; // buffer to record raw frame nibbles before parsing
68
int16_t pos_ = 0; // position in the buffer recording nibble frames before parsing
69
AP_HAL::UARTDriver* _port; // UART interface port reference to be used for SLCAN iface
70
71
ObjectBuffer<AP_HAL::CANIface::CanRxItem> rx_queue_; // Parsed Rx Frame queue
72
73
const uint32_t _serial_lock_key = 0x53494442; // Key used to lock UART port for use by slcan
74
75
AP_Int8 _slcan_can_port;
76
AP_Int8 _slcan_ser_port;
77
AP_Int8 _slcan_timeout;
78
AP_Int8 _slcan_start_delay;
79
80
bool _slcan_start_req;
81
uint32_t _slcan_start_req_time;
82
int8_t _prev_ser_port;
83
int8_t _iface_num = -1;
84
uint32_t _last_had_activity;
85
uint8_t num_tries;
86
AP_HAL::CANIface* _can_iface; // Can interface to be used for interaction by SLCAN interface
87
HAL_Semaphore port_sem;
88
bool _set_by_sermgr;
89
public:
90
CANIface():
91
rx_queue_(HAL_CAN_RX_QUEUE_SIZE)
92
{
93
AP_Param::setup_object_defaults(this, var_info);
94
}
95
96
static const struct AP_Param::GroupInfo var_info[];
97
98
bool init(const uint32_t bitrate, const OperatingMode mode) override
99
{
100
return false;
101
}
102
103
// Initialisation of SLCAN Passthrough method of operation
104
bool init_passthrough(uint8_t i);
105
106
void set_can_iface(AP_HAL::CANIface* can_iface)
107
{
108
_can_iface = can_iface;
109
}
110
111
void reset_params();
112
113
// Overriden methods
114
bool set_event_handle(AP_HAL::BinarySemaphore *sem_handle) override;
115
uint16_t getNumFilters() const override;
116
uint32_t getErrorCount() const override;
117
void get_stats(ExpandingString &) override;
118
bool is_busoff() const override;
119
bool configureFilters(const CanFilterConfig* filter_configs, uint16_t num_configs) override;
120
void flush_tx() override;
121
void clear_rx() override;
122
bool is_initialized() const override;
123
bool select(bool &read, bool &write,
124
const AP_HAL::CANFrame* const pending_tx,
125
uint64_t blocking_deadline) override;
126
int16_t send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline,
127
AP_HAL::CANIface::CanIOFlags flags) override;
128
129
int16_t receive(AP_HAL::CANFrame& out_frame, uint64_t& rx_time,
130
AP_HAL::CANIface::CanIOFlags& out_flags) override;
131
132
protected:
133
int8_t get_iface_num() const override {
134
return _iface_num;
135
}
136
137
bool add_to_rx_queue(const AP_HAL::CANIface::CanRxItem &frm) override {
138
return rx_queue_.push(frm);
139
}
140
};
141
142
}
143
144
#endif // AP_CAN_SLCAN_ENABLED
145
146