APM:Libraries
CAN.h
Go to the documentation of this file.
1 /* Copyright (C) 2017 Eugene Shamaev
2  *
3  * This file is free software: you can redistribute it and/or modify it
4  * under the terms of the GNU General Public License as published by the
5  * Free Software Foundation, either version 3 of the License, or
6  * (at your option) any later version.
7  *
8  * This file is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
11  * See the GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License along
14  * with this program. If not, see <http://www.gnu.org/licenses/>.
15  */
16 
17 #pragma once
18 
19 #include "AP_HAL_SITL.h"
20 
21 #if HAL_WITH_UAVCAN
22 #include <AP_HAL/CAN.h>
23 
24 class HALSITL::HALSITLCAN : public AP_HAL::CAN {
25 public:
26  HALSITLCAN() { }
27  ~HALSITLCAN() { }
28  int16_t send(const uavcan::CanFrame& frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags) override;
29  int16_t receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic, uavcan::UtcTime& out_ts_utc,
30  uavcan::CanIOFlags& out_flags) override;
31  int16_t configureFilters(const uavcan::CanFilterConfig* filter_configs, uint16_t num_configs) override;
32  uint16_t getNumFilters() const override;
33  uint64_t getErrorCount() const override;
34 
35  bool begin(uint32_t bitrate) override;
36  void end() override;
37  void reset() override;
38  bool is_initialized() override;
39  int32_t tx_pending() override;
40  int32_t available() override;
41 
42 
43 private:
44  uint32_t _baudrate;
45  volatile bool _initialised;
46  volatile bool _in_timer;
47 };
48 
49 class HALSITL::HALSITLCANDriver : public AP_HAL::CANManager
50 {
51 public:
52  HALSITLCANDriver() { }
53  ~HALSITLCANDriver() { }
54  uavcan::ICanIface* getIface(uint8_t iface_index) override;
55  const uavcan::ICanIface* getIface(uint8_t iface_index) const override;
56  uint8_t getNumIfaces() const override;
57  int16_t select(uavcan::CanSelectMasks& inout_masks,
58  const uavcan::CanFrame* (& pending_tx)[uavcan::MaxCanIfaces],
59  uavcan::MonotonicTime blocking_deadline) override;
60 };
61 
62 #endif
void reset()