Program Listing for File socket_can_id.hpp

Return to documentation for file (/tmp/ws/src/ros2_socketcan/ros2_socketcan/include/ros2_socketcan/socket_can_id.hpp)

// Copyright 2021 the Autoware Foundation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
// Co-developed by Tier IV, Inc. and Apex.AI, Inc.
#ifndef ROS2_SOCKETCAN__SOCKET_CAN_ID_HPP_
#define ROS2_SOCKETCAN__SOCKET_CAN_ID_HPP_

#include <cstdint>
#include <stdexcept>

#include "ros2_socketcan/visibility_control.hpp"

namespace drivers
{
namespace socketcan
{

constexpr std::size_t MAX_DATA_LENGTH = 8U;
constexpr std::size_t MAX_FD_DATA_LENGTH = 64U;
class SOCKETCAN_PUBLIC SocketCanTimeout : public std::runtime_error
{
public:
  explicit SocketCanTimeout(const char * const what)
  : runtime_error{what} {}
};  // class SocketCanTimeout

enum class FrameType : uint32_t
{
  DATA,
  ERROR,
  REMOTE
  // SocketCan doesn't support Overload frame directly?
};  // enum class FrameType

struct StandardFrame_ {};
//lint -e{1502} NOLINT It's a tag
constexpr StandardFrame_ StandardFrame;
struct ExtendedFrame_ {};
//lint -e{1502} NOLINT It's a tag
constexpr ExtendedFrame_ ExtendedFrame;

class SOCKETCAN_PUBLIC CanId
{
public:
  using IdT = uint32_t;
  using LengthT = uint32_t;
  // Default constructor: standard data frame with id 0
  CanId() = default;
  explicit CanId(const IdT raw_id, const uint64_t bus_time, const LengthT data_length = 0U);
  CanId(const IdT id, const uint64_t bus_time, FrameType type, StandardFrame_);
  CanId(const IdT id, const uint64_t bus_time, FrameType type, ExtendedFrame_);

  CanId & standard() noexcept;
  CanId & extended() noexcept;
  CanId & error_frame() noexcept;
  CanId & remote_frame() noexcept;
  CanId & data_frame() noexcept;
  CanId & frame_type(const FrameType type);
  CanId & identifier(const IdT id);

  IdT identifier() const noexcept;
  IdT get() const noexcept;
  bool is_extended() const noexcept;
  FrameType frame_type() const;
  LengthT length() const noexcept;

  uint64_t get_bus_time() {return bus_time;}

private:
  SOCKETCAN_LOCAL CanId(const IdT id, const uint64_t bus_time, FrameType type, bool is_extended);

  IdT m_id{};
  LengthT m_data_length{};
  uint64_t bus_time;
};  // class CanId
}  // namespace socketcan
}  // namespace drivers

#endif  // ROS2_SOCKETCAN__SOCKET_CAN_ID_HPP_