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_CANSensor.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
/*
16
generic CAN sensor class, for easy creation of CAN sensors using proprietary protocols
17
*/
18
#include <AP_HAL/AP_HAL.h>
19
20
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
21
22
#include <AP_Scheduler/AP_Scheduler.h>
23
#include "AP_CANSensor.h"
24
#include <AP_BoardConfig/AP_BoardConfig.h>
25
26
extern const AP_HAL::HAL& hal;
27
28
#if HAL_CANMANAGER_ENABLED
29
#define debug_can(level_debug, fmt, args...) do { AP::can().log_text(level_debug, _driver_name, fmt, ##args); } while (0)
30
#else
31
#define debug_can(level_debug, fmt, args...)
32
#endif
33
34
CANSensor::CANSensor(const char *driver_name, uint16_t stack_size) :
35
_driver_name(driver_name),
36
_stack_size(stack_size)
37
{}
38
39
40
void CANSensor::register_driver(AP_CAN::Protocol dtype)
41
{
42
#if HAL_CANMANAGER_ENABLED
43
if (!AP::can().register_driver(dtype, this)) {
44
if (AP::can().register_11bit_driver(dtype, this, _driver_index)) {
45
is_aux_11bit_driver = true;
46
_can_driver = AP::can().get_driver(_driver_index);
47
_initialized = true;
48
} else {
49
debug_can(AP_CANManager::LOG_ERROR, "Failed to register CANSensor %s", _driver_name);
50
}
51
} else {
52
debug_can(AP_CANManager::LOG_INFO, "%s: constructed", _driver_name);
53
}
54
#elif defined(HAL_BUILD_AP_PERIPH)
55
register_driver_periph(dtype);
56
#endif
57
}
58
59
60
#ifdef HAL_BUILD_AP_PERIPH
61
CANSensor::CANSensor_Periph CANSensor::_periph[HAL_NUM_CAN_IFACES];
62
63
void CANSensor::register_driver_periph(const AP_CAN::Protocol dtype)
64
{
65
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
66
if (_periph[i].protocol != dtype) {
67
continue;
68
}
69
70
if (!add_interface(_periph[i].iface)) {
71
continue;
72
}
73
74
init(0, false); // TODO: allow multiple drivers
75
return;
76
}
77
}
78
#endif
79
80
void CANSensor::init(uint8_t driver_index, bool enable_filters)
81
{
82
_driver_index = driver_index;
83
84
debug_can(AP_CANManager::LOG_INFO, "starting init");
85
86
if (_initialized) {
87
debug_can(AP_CANManager::LOG_ERROR, "already initialized");
88
return;
89
}
90
91
#ifndef HAL_BUILD_AP_PERIPH
92
// get CAN manager instance
93
_can_driver = AP::can().get_driver(driver_index);
94
95
if (_can_driver == nullptr) {
96
debug_can(AP_CANManager::LOG_ERROR, "no CAN driver");
97
return;
98
}
99
#endif
100
101
// start thread for receiving and sending CAN frames
102
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&CANSensor::loop, void), _driver_name, _stack_size, AP_HAL::Scheduler::PRIORITY_CAN, 0)) {
103
debug_can(AP_CANManager::LOG_ERROR, "couldn't create thread");
104
return;
105
}
106
107
_initialized = true;
108
109
debug_can(AP_CANManager::LOG_INFO, "init done");
110
}
111
112
bool CANSensor::add_interface(AP_HAL::CANIface* can_iface)
113
{
114
if (_can_iface != nullptr) {
115
debug_can(AP_CANManager::LOG_ERROR, "Multiple Interface not supported");
116
return false;
117
}
118
119
_can_iface = can_iface;
120
121
if (_can_iface == nullptr) {
122
debug_can(AP_CANManager::LOG_ERROR, "CAN driver not found");
123
return false;
124
}
125
126
if (!_can_iface->is_initialized()) {
127
debug_can(AP_CANManager::LOG_ERROR, "Driver not initialized");
128
return false;
129
}
130
131
if (!_can_iface->set_event_handle(&sem_handle)) {
132
debug_can(AP_CANManager::LOG_ERROR, "Cannot add event handle");
133
return false;
134
}
135
return true;
136
}
137
138
bool CANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us)
139
{
140
if (!_initialized) {
141
debug_can(AP_CANManager::LOG_ERROR, "Driver not initialized for write_frame");
142
return false;
143
}
144
145
if (is_aux_11bit_driver && _can_driver != nullptr) {
146
return _can_driver->write_aux_frame(out_frame, timeout_us);
147
}
148
149
bool read_select = false;
150
bool write_select = true;
151
bool ret = _can_iface->select(read_select, write_select, &out_frame, AP_HAL::micros64() + timeout_us);
152
if (!ret || !write_select) {
153
return false;
154
}
155
156
uint64_t deadline = AP_HAL::micros64() + 2000000;
157
return (_can_iface->send(out_frame, deadline, AP_HAL::CANIface::AbortOnError) == 1);
158
}
159
160
void CANSensor::loop()
161
{
162
while (!hal.scheduler->is_system_initialized()) {
163
// don't process packets till startup complete
164
hal.scheduler->delay(1);
165
}
166
167
#ifdef HAL_BUILD_AP_PERIPH
168
const uint32_t LOOP_INTERVAL_US = 1000;
169
#else
170
const uint32_t LOOP_INTERVAL_US = AP::scheduler().get_loop_period_us();
171
#endif
172
173
while (true) {
174
uint64_t deadline_us = AP_HAL::micros64() + LOOP_INTERVAL_US;
175
176
// wait to receive frame
177
bool read_select = true;
178
bool write_select = false;
179
bool ret = _can_iface->select(read_select, write_select, nullptr, deadline_us);
180
if (ret && read_select) {
181
uint64_t time;
182
AP_HAL::CANIface::CanIOFlags flags {};
183
184
AP_HAL::CANFrame frame;
185
int16_t res = _can_iface->receive(frame, time, flags);
186
187
if (res == 1) {
188
handle_frame(frame);
189
}
190
}
191
}
192
}
193
194
MultiCAN::MultiCANLinkedList* MultiCAN::callbacks;
195
196
MultiCAN::MultiCAN(ForwardCanFrame cf, AP_CAN::Protocol can_type, const char *driver_name) :
197
CANSensor(driver_name)
198
{
199
if (callbacks == nullptr) {
200
callbacks = NEW_NOTHROW MultiCANLinkedList();
201
}
202
if (callbacks == nullptr) {
203
AP_BoardConfig::allocation_error("Failed to create multican callback");
204
}
205
206
// Register new driver
207
register_driver(can_type);
208
callbacks->register_callback(cf);
209
}
210
211
// handle a received frame from the CAN bus
212
void MultiCAN::handle_frame(AP_HAL::CANFrame &frame)
213
{
214
if (callbacks != nullptr) {
215
callbacks->handle_frame(frame);
216
}
217
218
}
219
220
// register a callback for a CAN frame by adding it to the linked list
221
void MultiCAN::MultiCANLinkedList::register_callback(ForwardCanFrame callback)
222
{
223
CANSensor_Multi* newNode = NEW_NOTHROW CANSensor_Multi();
224
if (newNode == nullptr) {
225
AP_BoardConfig::allocation_error("Failed to create multican node");
226
}
227
WITH_SEMAPHORE(sem);
228
{
229
newNode->_callback = callback;
230
newNode->next = head;
231
head = newNode;
232
}
233
}
234
235
// distribute the CAN frame to the registered callbacks
236
void MultiCAN::MultiCANLinkedList::handle_frame(AP_HAL::CANFrame &frame)
237
{
238
WITH_SEMAPHORE(sem);
239
for (CANSensor_Multi* current = head; current != nullptr; current = current->next) {
240
if (current->_callback(frame)) {
241
return;
242
}
243
}
244
}
245
246
#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS
247
248
249