Autoware.Auto
vlp16_integration_spoofer.hpp
Go to the documentation of this file.
1 // Copyright 2017-2018 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.
16 
17 #ifndef LIDAR_INTEGRATION__VLP16_INTEGRATION_SPOOFER_HPP_
18 #define LIDAR_INTEGRATION__VLP16_INTEGRATION_SPOOFER_HPP_
19 
20 #include <common/types.hpp>
23 #include <thread>
24 #include <atomic>
25 
26 namespace lidar_integration
27 {
32 
33 class LIDAR_INTEGRATION_PUBLIC Vlp16IntegrationSpoofer
34 {
35 public:
37  const char8_t * const ip,
38  const uint16_t port,
39  const float32_t rpm);
41 
42  void start();
43 
44  void stop();
45 
46  const uint32_t & send_count() const {return m_spoofer.send_count();}
47 
49  static constexpr float32_t MIN_RPM = 300.0F;
51  static constexpr float32_t MAX_RPM = 1200.0F;
52 
53 private:
54  class SpoofTask
55  {
56 public:
57  SpoofTask(
58  const char8_t * const ip,
59  const uint16_t port,
60  const float32_t rpm,
61  const std::atomic_bool & running);
62 
63  const uint32_t & send_count() const {return m_send_count;}
64 
65  void start()
66  {
67  m_thread = std::thread{[this] {task_function();}};
68  }
69 
70  void stop()
71  {
72  if (m_thread.joinable()) {
73  m_thread.join();
74  }
75  }
76 
77 protected:
78  void task_function();
79 
80 private:
81  static constexpr uint32_t RAY_SIZE = 16U;
82  // SENSOR SPECIFIC CONSTANTS
84  static constexpr uint16_t AZIMUTH_ROTATION_RESOLUTION = 36000U;
86  static constexpr float32_t DEG2IDX =
87  static_cast<float32_t>(AZIMUTH_ROTATION_RESOLUTION) / 360.0F;
89  static constexpr uint32_t NUM_INTENSITY_VALUES = 256U;
90 
93  static constexpr uint16_t NUM_BLOCKS_PER_PACKET = 12U;
95  static constexpr uint16_t NUM_POINTS_PER_BLOCK = 32U;
96 
98  static constexpr float32_t FIRE_SEQ_OFFSET_US = 55.296F;
100  static constexpr float32_t FIRE_DURATION_US = 2.304F;
101 
104  struct DataChannel
105  {
106  uint8_t data[3U];
107  };
108 
110  struct DataBlock
111  {
112  uint8_t flag[2U];
113  uint8_t azimuth_bytes[2U];
114  DataChannel channels[NUM_POINTS_PER_BLOCK];
115  };
116 
118  struct Packet
119  {
120  DataBlock blocks[NUM_BLOCKS_PER_PACKET];
121  uint8_t timestamp_bytes[4U];
122  uint8_t factory_bytes[2U];
123  };
124 
125  static void uint16_to_bytes(const uint16_t val, uint8_t arr[]);
126 
127  static uint16_t bytes_to_uint16(const uint8_t arr[]);
128 
129  static void update_packet_azimuth(Packet & pkt, const uint16_t dth_tic);
130 
131  void init_packet(
132  Packet & pkt,
133  const float32_t rpm,
134  const uint16_t (& distances)[RAY_SIZE]) const;
135 
136  void initialize_packets(const float32_t rpm);
137 
138  // make sure packet sizes are correct
139  static_assert(sizeof(DataChannel) == 3U, "Error VLP16 data channel size is incorrect");
140  static_assert(sizeof(DataBlock) == 100U, "Error VLP16 data block size is incorrect");
141  static_assert(sizeof(Packet) == 1206U, "Error VLP16 packet size is incorrect");
142 
143  UdpSender<Packet> m_udp_sender;
144  std::chrono::steady_clock::time_point m_last_send_time;
145  Packet m_all_flat_ground_packet;
146  Packet m_flat_ground_wall_packet;
147  const std::atomic_bool & m_running;
148  const std::chrono::nanoseconds m_send_period;
149  uint16_t m_azimuth_increment;
150  uint32_t m_send_count = 0;
151  std::thread m_thread;
152  }; // SpoofTask
153 
154  std::atomic_bool m_running;
155  SpoofTask m_spoofer;
156 }; // Vlp16IntegrationSpoofer
157 
158 } // namespace lidar_integration
159 #endif // LIDAR_INTEGRATION__VLP16_INTEGRATION_SPOOFER_HPP_
lidar_integration::MIN_RPM
static constexpr float32_t MIN_RPM
rpm min speed
Definition: vlp16_integration_spoofer.cpp:55
lidar_integration::NUM_POINTS_PER_BLOCK
static constexpr uint16_t NUM_POINTS_PER_BLOCK
number of points stored in a data block
Definition: vlp16_integration_spoofer.cpp:128
lidar_integration
Definition: lidar_integration.hpp:26
types.hpp
This file includes common type definition.
lidar_integration::NUM_INTENSITY_VALUES
static constexpr uint32_t NUM_INTENSITY_VALUES
how intensity is quantized: 1 byte = 256 possible values
Definition: vlp16_integration_spoofer.cpp:122
UdpSender
Definition: udp_sender.hpp:44
visibility_control.hpp
lidar_integration::MAX_RPM
static constexpr float32_t MAX_RPM
rpm max speed
Definition: vlp16_integration_spoofer.cpp:57
lidar_integration::DEG2IDX
static constexpr float32_t DEG2IDX
conversion from a degree (vlp) to idx
Definition: vlp16_integration_spoofer.cpp:119
autoware::common::types::char8_t
char char8_t
Definition: types.hpp:40
udp_sender.hpp
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
lidar_integration::FIRE_SEQ_OFFSET_US
static constexpr float32_t FIRE_SEQ_OFFSET_US
full (16 point) fire sequence takes this long to cycle
Definition: vlp16_integration_spoofer.cpp:131
lidar_integration::FIRE_DURATION_US
static constexpr float32_t FIRE_DURATION_US
one laser fires for this long
Definition: vlp16_integration_spoofer.cpp:133
lidar_integration::NUM_BLOCKS_PER_PACKET
static constexpr uint16_t NUM_BLOCKS_PER_PACKET
Definition: vlp16_integration_spoofer.cpp:126
lidar_integration::Vlp16IntegrationSpoofer::send_count
const uint32_t & send_count() const
Definition: vlp16_integration_spoofer.hpp:46
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
lidar_integration::RAY_SIZE
static constexpr uint32_t RAY_SIZE
Definition: vlp16_integration_spoofer.cpp:114
lidar_integration::AZIMUTH_ROTATION_RESOLUTION
static constexpr uint16_t AZIMUTH_ROTATION_RESOLUTION
resolution of azimuth angle: number of points in a full rotation
Definition: vlp16_integration_spoofer.cpp:117
lidar_integration::Vlp16IntegrationSpoofer
Definition: vlp16_integration_spoofer.hpp:33
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:47