AP_HAL: top level HAL definitions for CAN bus driver

This commit is contained in:
Eugene Shamaev 2017-04-02 17:54:31 +03:00 committed by Francisco Ferreira
parent 7cd290af9b
commit 9b98c304c4
5 changed files with 133 additions and 2 deletions

View File

@ -19,6 +19,10 @@
#include "Util.h" #include "Util.h"
#include "OpticalFlow.h" #include "OpticalFlow.h"
#if HAL_WITH_UAVCAN
#include "CAN.h"
#endif
#include "utility/Print.h" #include "utility/Print.h"
#include "utility/Stream.h" #include "utility/Stream.h"
#include "utility/BetterStream.h" #include "utility/BetterStream.h"

View File

@ -29,6 +29,9 @@ namespace AP_HAL {
class Semaphore; class Semaphore;
class OpticalFlow; class OpticalFlow;
class CANManager;
class CAN;
class Util; class Util;
/* Utility Classes */ /* Utility Classes */

116
libraries/AP_HAL/CAN.h Normal file
View File

@ -0,0 +1,116 @@
/*
* Copyright (C) 2017 Eugene Shamaev
*
* 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/>.
*/
#pragma once
#include <inttypes.h>
#include <string.h>
#include <assert.h>
#include <cmath>
#if HAL_WITH_UAVCAN
#include "AP_HAL_Namespace.h"
#include "utility/functor.h"
#include <uavcan/driver/can.hpp>
#include <uavcan/time.hpp>
class AP_UAVCAN;
/**
* Single non-blocking CAN interface.
*/
class AP_HAL::CAN: public uavcan::ICanIface {
public:
/* CAN port open method
bitrate Selects the speed that the port will be configured to. If zero, the port speed is left unchanged.
return false - CAN port open failed
true - CAN port open succeeded
*/
virtual bool begin(uint32_t bitrate) = 0;
/*
CAN port close
*/
virtual void end() = 0;
/*
Reset opened CAN port
Pending messages to be transmitted are deleted and receive state and FIFO also reset.
All pending errors are cleared.
*/
virtual void reset() = 0;
/*
Test if CAN port is opened and initialized
return false - CAN port not initialized
true - CAN port is initialized
*/
virtual bool is_initialized() = 0;
/*
Return if CAN port has some untransmitted pending messages
return -1 - CAN port is not opened or initialized
0 - no messages are pending
positive - number of pending messages
*/
virtual int32_t tx_pending() = 0;
/*
Return if CAN port has received but yet read messages
return -1 - CAN port is not opened or initialized
0 - no messages are pending for read
positive - number of pending messages for read
*/
virtual int32_t available() = 0;
};
/**
* Generic CAN driver.
*/
class AP_HAL::CANManager: public uavcan::ICanDriver {
public:
/* CAN port open method
Opens port with specified bit rate
bitrate - selects the speed that the port will be configured to. If zero, the port speed is left
unchanged.
can_number - the index of can interface to be opened
return false - CAN port open failed
true - CAN port open succeeded
*/
virtual bool begin(uint32_t bitrate, uint8_t can_number) = 0;
/*
Test if CAN manager is ready and initialized
return false - CAN manager not initialized
true - CAN manager is initialized
*/
virtual bool is_initialized() = 0;
virtual AP_UAVCAN *get_UAVCAN(void);
virtual void set_UAVCAN(AP_UAVCAN *uavcan);
};
#endif

View File

@ -11,6 +11,9 @@
#include "UARTDriver.h" #include "UARTDriver.h"
#include "system.h" #include "system.h"
#include "OpticalFlow.h" #include "OpticalFlow.h"
#if HAL_WITH_UAVCAN
#include "CAN.h"
#endif
class AP_HAL::HAL { class AP_HAL::HAL {
public: public:
@ -30,7 +33,8 @@ public:
AP_HAL::RCOutput* _rcout, AP_HAL::RCOutput* _rcout,
AP_HAL::Scheduler* _scheduler, AP_HAL::Scheduler* _scheduler,
AP_HAL::Util* _util, AP_HAL::Util* _util,
AP_HAL::OpticalFlow *_opticalflow) AP_HAL::OpticalFlow *_opticalflow,
AP_HAL::CANManager* _can_mgr)
: :
uartA(_uartA), uartA(_uartA),
uartB(_uartB), uartB(_uartB),
@ -48,7 +52,8 @@ public:
rcout(_rcout), rcout(_rcout),
scheduler(_scheduler), scheduler(_scheduler),
util(_util), util(_util),
opticalflow(_opticalflow) opticalflow(_opticalflow),
can_mgr(_can_mgr)
{ {
AP_HAL::init(); AP_HAL::init();
} }
@ -88,4 +93,5 @@ public:
AP_HAL::Scheduler* scheduler; AP_HAL::Scheduler* scheduler;
AP_HAL::Util *util; AP_HAL::Util *util;
AP_HAL::OpticalFlow *opticalflow; AP_HAL::OpticalFlow *opticalflow;
AP_HAL::CANManager* can_mgr;
}; };

View File

@ -60,4 +60,6 @@ public:
optional function to stop clock at a given time, used by log replay optional function to stop clock at a given time, used by log replay
*/ */
virtual void stop_clock(uint64_t time_usec) {} virtual void stop_clock(uint64_t time_usec) {}
virtual void create_uavcan_thread() {};
}; };