Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_CANManager/AP_CANSensor.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15generic CAN sensor class, for easy creation of CAN sensors using proprietary protocols16*/17#include <AP_HAL/AP_HAL.h>1819#if HAL_MAX_CAN_PROTOCOL_DRIVERS2021#include <AP_Scheduler/AP_Scheduler.h>22#include "AP_CANSensor.h"23#include <AP_BoardConfig/AP_BoardConfig.h>2425extern const AP_HAL::HAL& hal;2627#if HAL_CANMANAGER_ENABLED28#define debug_can(level_debug, fmt, args...) do { AP::can().log_text(level_debug, _driver_name, fmt, ##args); } while (0)29#else30#define debug_can(level_debug, fmt, args...)31#endif3233CANSensor::CANSensor(const char *driver_name, uint16_t stack_size) :34_driver_name(driver_name),35_stack_size(stack_size)36{}373839void CANSensor::register_driver(AP_CAN::Protocol dtype)40{41#if HAL_CANMANAGER_ENABLED42if (!AP::can().register_driver(dtype, this)) {43if (AP::can().register_11bit_driver(dtype, this, _driver_index)) {44is_aux_11bit_driver = true;45_can_driver = AP::can().get_driver(_driver_index);46_initialized = true;47} else {48debug_can(AP_CANManager::LOG_ERROR, "Failed to register CANSensor %s", _driver_name);49}50} else {51debug_can(AP_CANManager::LOG_INFO, "%s: constructed", _driver_name);52}53#elif defined(HAL_BUILD_AP_PERIPH)54register_driver_periph(dtype);55#endif56}575859#ifdef HAL_BUILD_AP_PERIPH60CANSensor::CANSensor_Periph CANSensor::_periph[HAL_NUM_CAN_IFACES];6162void CANSensor::register_driver_periph(const AP_CAN::Protocol dtype)63{64for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {65if (_periph[i].protocol != dtype) {66continue;67}6869if (!add_interface(_periph[i].iface)) {70continue;71}7273init(0, false); // TODO: allow multiple drivers74return;75}76}77#endif7879void CANSensor::init(uint8_t driver_index, bool enable_filters)80{81_driver_index = driver_index;8283debug_can(AP_CANManager::LOG_INFO, "starting init");8485if (_initialized) {86debug_can(AP_CANManager::LOG_ERROR, "already initialized");87return;88}8990#ifndef HAL_BUILD_AP_PERIPH91// get CAN manager instance92_can_driver = AP::can().get_driver(driver_index);9394if (_can_driver == nullptr) {95debug_can(AP_CANManager::LOG_ERROR, "no CAN driver");96return;97}98#endif99100// start thread for receiving and sending CAN frames101if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&CANSensor::loop, void), _driver_name, _stack_size, AP_HAL::Scheduler::PRIORITY_CAN, 0)) {102debug_can(AP_CANManager::LOG_ERROR, "couldn't create thread");103return;104}105106_initialized = true;107108debug_can(AP_CANManager::LOG_INFO, "init done");109}110111bool CANSensor::add_interface(AP_HAL::CANIface* can_iface)112{113if (_can_iface != nullptr) {114debug_can(AP_CANManager::LOG_ERROR, "Multiple Interface not supported");115return false;116}117118_can_iface = can_iface;119120if (_can_iface == nullptr) {121debug_can(AP_CANManager::LOG_ERROR, "CAN driver not found");122return false;123}124125if (!_can_iface->is_initialized()) {126debug_can(AP_CANManager::LOG_ERROR, "Driver not initialized");127return false;128}129130if (!_can_iface->set_event_handle(&sem_handle)) {131debug_can(AP_CANManager::LOG_ERROR, "Cannot add event handle");132return false;133}134return true;135}136137bool CANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us)138{139if (!_initialized) {140debug_can(AP_CANManager::LOG_ERROR, "Driver not initialized for write_frame");141return false;142}143144if (is_aux_11bit_driver && _can_driver != nullptr) {145return _can_driver->write_aux_frame(out_frame, timeout_us);146}147148bool read_select = false;149bool write_select = true;150bool ret = _can_iface->select(read_select, write_select, &out_frame, AP_HAL::micros64() + timeout_us);151if (!ret || !write_select) {152return false;153}154155uint64_t deadline = AP_HAL::micros64() + 2000000;156return (_can_iface->send(out_frame, deadline, AP_HAL::CANIface::AbortOnError) == 1);157}158159void CANSensor::loop()160{161while (!hal.scheduler->is_system_initialized()) {162// don't process packets till startup complete163hal.scheduler->delay(1);164}165166#ifdef HAL_BUILD_AP_PERIPH167const uint32_t LOOP_INTERVAL_US = 1000;168#else169const uint32_t LOOP_INTERVAL_US = AP::scheduler().get_loop_period_us();170#endif171172while (true) {173uint64_t deadline_us = AP_HAL::micros64() + LOOP_INTERVAL_US;174175// wait to receive frame176bool read_select = true;177bool write_select = false;178bool ret = _can_iface->select(read_select, write_select, nullptr, deadline_us);179if (ret && read_select) {180uint64_t time;181AP_HAL::CANIface::CanIOFlags flags {};182183AP_HAL::CANFrame frame;184int16_t res = _can_iface->receive(frame, time, flags);185186if (res == 1) {187handle_frame(frame);188}189}190}191}192193MultiCAN::MultiCANLinkedList* MultiCAN::callbacks;194195MultiCAN::MultiCAN(ForwardCanFrame cf, AP_CAN::Protocol can_type, const char *driver_name) :196CANSensor(driver_name)197{198if (callbacks == nullptr) {199callbacks = NEW_NOTHROW MultiCANLinkedList();200}201if (callbacks == nullptr) {202AP_BoardConfig::allocation_error("Failed to create multican callback");203}204205// Register new driver206register_driver(can_type);207callbacks->register_callback(cf);208}209210// handle a received frame from the CAN bus211void MultiCAN::handle_frame(AP_HAL::CANFrame &frame)212{213if (callbacks != nullptr) {214callbacks->handle_frame(frame);215}216217}218219// register a callback for a CAN frame by adding it to the linked list220void MultiCAN::MultiCANLinkedList::register_callback(ForwardCanFrame callback)221{222CANSensor_Multi* newNode = NEW_NOTHROW CANSensor_Multi();223if (newNode == nullptr) {224AP_BoardConfig::allocation_error("Failed to create multican node");225}226WITH_SEMAPHORE(sem);227{228newNode->_callback = callback;229newNode->next = head;230head = newNode;231}232}233234// distribute the CAN frame to the registered callbacks235void MultiCAN::MultiCANLinkedList::handle_frame(AP_HAL::CANFrame &frame)236{237WITH_SEMAPHORE(sem);238for (CANSensor_Multi* current = head; current != nullptr; current = current->next) {239if (current->_callback(frame)) {240return;241}242}243}244245#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS246247248249