Autoware.Auto
socket_can_receiver.hpp
Go to the documentation of this file.
1 // Copyright 2019 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
18 #ifndef SOCKETCAN__SOCKET_CAN_RECEIVER_HPP_
19 #define SOCKETCAN__SOCKET_CAN_RECEIVER_HPP_
20 
23 
24 #include <array>
25 #include <chrono>
26 #include <cstring>
27 #include <string>
28 
29 namespace autoware
30 {
31 namespace drivers
32 {
33 namespace socketcan
34 {
35 
38 {
39 public:
41  explicit SocketCanReceiver(const std::string & interface = "can0");
43  ~SocketCanReceiver() noexcept;
44 
52  CanId receive(
53  void * const data,
54  const std::chrono::nanoseconds timeout = std::chrono::nanoseconds::zero()) const;
65  template<typename T, typename = std::enable_if_t<!std::is_pointer<T>::value>>
67  T & data,
68  const std::chrono::nanoseconds timeout = std::chrono::nanoseconds::zero()) const
69  {
70  static_assert(sizeof(data) <= MAX_DATA_LENGTH, "Data type too large for CAN");
71  std::array<uint8_t, MAX_DATA_LENGTH> data_raw{};
72  const auto ret = receive(&data_raw[0U], timeout);
73  if (ret.length() != sizeof(data)) {
74  throw std::runtime_error{"Received CAN data is of size incompatible with provided type!"};
75  }
76  (void)std::memcpy(&data, &data_raw[0U], ret.length());
77  return ret;
78  }
79 
80 private:
81  // Wait for file descriptor to be available to send data via select()
82  SOCKETCAN_LOCAL void wait(const std::chrono::nanoseconds timeout) const;
83 
84  int32_t m_file_descriptor;
85 }; // class SocketCanReceiver
86 
87 } // namespace socketcan
88 } // namespace drivers
89 } // namespace autoware
90 
91 #endif // SOCKETCAN__SOCKET_CAN_RECEIVER_HPP_
visibility_control.hpp
catr_diff.T
T
Definition: catr_diff.py:22
autoware::drivers::socketcan::MAX_DATA_LENGTH
constexpr std::size_t MAX_DATA_LENGTH
Definition: socket_can_id.hpp:36
autoware::drivers::socketcan::SocketCanReceiver
Simple RAII wrapper around a raw CAN receiver.
Definition: socket_can_receiver.hpp:37
SOCKETCAN_PUBLIC
#define SOCKETCAN_PUBLIC
Definition: drivers/socketcan/include/socketcan/visibility_control.hpp:44
SOCKETCAN_LOCAL
#define SOCKETCAN_LOCAL
Definition: drivers/socketcan/include/socketcan/visibility_control.hpp:45
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::drivers::socketcan::CanId
Definition: socket_can_id.hpp:64
autoware::drivers::socketcan::SocketCanReceiver::receive
CanId receive(T &data, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds::zero()) const
Definition: socket_can_receiver.hpp:66
socket_can_id.hpp
This file defines a class a socket sender.