hfl_driver  0.0.20
ROS driver for Continental's HFL110 3D Flash Lidar
hfl110dcu.h
Go to the documentation of this file.
1 // Copyright 2020 Continental AG
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD 2-Clause Simplified License)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
18 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
19 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
20 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
21 // COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
22 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
23 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
24 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
26 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
27 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28 // POSSIBILITY OF SUCH DAMAGE.
29 
30 
36 #ifndef IMAGE_PROCESSOR__HFL110DCU_H_
37 #define IMAGE_PROCESSOR__HFL110DCU_H_
38 
39 #include <base_hfl110dcu.h>
40 
41 #include <angles/angles.h>
42 #include <arpa/inet.h>
43 #include <camera_info_manager/camera_info_manager.h>
44 #include <cv_bridge/cv_bridge.h>
45 #include <geometry_msgs/TransformStamped.h>
46 #include <image_transport/image_transport.h>
47 #include <image_geometry/pinhole_camera_model.h>
48 #include <ros/package.h>
49 #include <tf2/LinearMath/Quaternion.h>
50 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
51 #include <tf2_ros/transform_broadcaster.h>
52 #include <geometry_msgs/Point.h>
53 #include <sensor_msgs/PointCloud2.h>
54 #include <sensor_msgs/point_cloud2_iterator.h>
55 #include <visualization_msgs/Marker.h>
56 #include <visualization_msgs/MarkerArray.h>
57 
58 #include <string>
59 #include <vector>
60 #include <cmath>
61 #include <memory>
62 
63 #include "ros/ros.h"
64 
65 
66 #define HFL110_MAGIC_NUMBER_16_BIT 0.000762951 // 50 / 2^16
67 
68 const float NO_RETURN_DISTANCES = NAN;
69 
70 namespace hfl
71 {
74 {
75  uint16_t range;
76  uint16_t intensity;
77  uint16_t range2;
78  uint16_t intensity2;
79 };
80 
83 {
84  uint16_t udp_version;
85  uint16_t pca_version;
86  uint64_t timeStamp;
88  uint32_t image_row_number;
89 };
90 
93 {
94  float_t fx;
95  float_t fy;
96  float_t ux;
97  float_t uy;
98  float_t r1;
99  float_t r2;
100  float_t t1;
101  float_t t2;
102  float_t r3;
103 };
104 
107 {
108  float_t intrinsic_yaw;
110  float_t extrinsic_yaw;
112  float_t extrinsic_roll;
116  uint32_t status;
117 };
118 
120 struct UdpFrame
121 {
126  uint8_t pixel_type[128];
127 };
128 
130 struct objGeo
131 {
132  float x_rear_r;
133  float y_rear_r;
134  float x_rear_l;
135  float y_rear_l;
136  float x_front_l;
137  float y_front_l;
138  float height;
140  float fDistX;
141  float fDistY;
142  float yaw;
143 };
144 
146 struct objKin
147 {
148  float fVabsX;
149  float fVabsY;
150  float fVrelX;
151  float fVrelY;
152  float fAabsX;
153  float fDistXDistY;
154  float fDistXVx;
155  float fDistXVy;
156  float fDistXAx;
157  float fDistXAy;
158  float fDistYVx;
159  float fDistYVy;
160  float fDistYAx;
161  float fDistYAy;
162  float fVxVy;
163  float fVxAx;
164  float fVxAy;
165  float fVyAx;
166  float fVyAy;
167  float fAxAy;
168 };
169 
171 struct objState
172 {
174  unsigned TP_OBJ_MT_STATE_NEW : 1;
179 };
180 
182 struct objDyn
183 {
192 };
193 
195 struct hflObj
196 {
201  uint8_t quality;
202  uint8_t classification;
203  uint8_t confidence;
204 };
205 
209 class HFL110DCU : public BaseHFL110DCU
210 {
211 public:
220  HFL110DCU(std::string model, std::string version,
221  std::string frame_id, ros::NodeHandle& node_handler);
222 
230  bool parseFrame(int start_byte, const std::vector<uint8_t>& packet) override;
231 
239  bool processFrameData(const std::vector<uint8_t>& data) override;
240 
248  bool parseObjects(int start_byte, const std::vector<uint8_t>& packet) override;
249 
257  bool processObjectData(const std::vector<uint8_t>& data) override;
258 
260  cv::Mat initTransform(cv::Mat cameraMatrix, cv::Mat distCoeffs,
261  int width, int height, bool radial);
262 
263 private:
265  ros::NodeHandle node_handler_;
266 
269 
271  std::shared_ptr<std_msgs::Header> frame_header_message_;
272 
274  std::shared_ptr<std_msgs::Header> object_header_message_;
275 
277  std::shared_ptr<std_msgs::Header> tf_header_message_;
278 
280  uint8_t row_, col_;
281 
283  uint8_t expected_packet_ = 0;
284 
287 
288  // Camera info manager
289  camera_info_manager::CameraInfoManager *camera_info_manager_;
290 
292  cv_bridge::CvImagePtr p_image_depth_;
293 
295  cv_bridge::CvImagePtr p_image_intensity_;
296 
298  image_transport::CameraPublisher pub_depth_;
299 
301  image_transport::CameraPublisher pub_depth2_;
302 
304  image_transport::CameraPublisher pub_intensity_;
305 
307  image_transport::CameraPublisher pub_intensity2_;
308 
310  ros::Publisher pub_objects_;
311 
313  std::vector<hflObj> objects_;
314 
316  ros::Publisher pub_points_;
317 
319  std::shared_ptr<sensor_msgs::PointCloud2> pointcloud_;
320 
322  geometry_msgs::TransformStamped global_tf_;
323 
325  cv::Mat transform_;
326 
328  cv_bridge::CvImagePtr p_image_depth2_;
329 
331  cv_bridge::CvImagePtr p_image_intensity2_;
332 };
333 } // namespace hfl
334 #endif // IMAGE_PROCESSOR__HFL110DCU_H_
This file defines the HFL110DCU camera base class.
Base class for the HFL110DCU cameras.
Definition: base_hfl110dcu.h:73
Implements the HFL110DCU camera image parsing and publishing.
Definition: hfl110dcu.h:210
cv::Mat initTransform(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial)
Definition: hfl110dcu.cpp:628
ros::NodeHandle node_handler_
ROS node handler.
Definition: hfl110dcu.h:265
cv_bridge::CvImagePtr p_image_depth_
Pointer to depth image.
Definition: hfl110dcu.h:292
bool processFrameData(const std::vector< uint8_t > &data) override
Definition: hfl110dcu.cpp:216
geometry_msgs::TransformStamped global_tf_
ROS Transform.
Definition: hfl110dcu.h:322
image_transport::CameraPublisher pub_intensity_
16 bit Intensity image publisher
Definition: hfl110dcu.h:304
cv_bridge::CvImagePtr p_image_depth2_
Pointer to depth image second return.
Definition: hfl110dcu.h:328
camera_info_manager::CameraInfoManager * camera_info_manager_
Definition: hfl110dcu.h:289
bool parseObjects(int start_byte, const std::vector< uint8_t > &packet) override
Definition: hfl110dcu.cpp:437
std::shared_ptr< std_msgs::Header > tf_header_message_
TF Header message.
Definition: hfl110dcu.h:277
ros::Publisher pub_objects_
Objects publisher.
Definition: hfl110dcu.h:310
cv_bridge::CvImagePtr p_image_intensity2_
Pointer to 16 bit intensity image second return.
Definition: hfl110dcu.h:331
std::shared_ptr< std_msgs::Header > frame_header_message_
Frame Header message.
Definition: hfl110dcu.h:271
bool parseFrame(int start_byte, const std::vector< uint8_t > &packet) override
Definition: hfl110dcu.cpp:102
cv::Mat transform_
Transform.
Definition: hfl110dcu.h:325
bool processObjectData(const std::vector< uint8_t > &data) override
Definition: hfl110dcu.cpp:503
std::shared_ptr< sensor_msgs::PointCloud2 > pointcloud_
Pointcloud msg.
Definition: hfl110dcu.h:319
std::shared_ptr< std_msgs::Header > object_header_message_
Object Header message.
Definition: hfl110dcu.h:274
cv_bridge::CvImagePtr p_image_intensity_
Pointer to 16 bit intensity image.
Definition: hfl110dcu.h:295
image_transport::CameraPublisher pub_intensity2_
16 bit Intensity image publisher return 2
Definition: hfl110dcu.h:307
uint8_t row_
Row and column Counter.
Definition: hfl110dcu.h:280
int bytes_received_
Received packet bytes from HFL110.
Definition: hfl110dcu.h:268
std::vector< hflObj > objects_
Objects vector;.
Definition: hfl110dcu.h:313
HFL110DCU(std::string model, std::string version, std::string frame_id, ros::NodeHandle &node_handler)
Definition: hfl110dcu.cpp:52
uint8_t expected_packet_
Return counter.
Definition: hfl110dcu.h:283
image_transport::CameraPublisher pub_depth2_
Depth image publisher second return 2.
Definition: hfl110dcu.h:301
float focal_length_
Focal Length.
Definition: hfl110dcu.h:286
image_transport::CameraPublisher pub_depth_
Depth image publisher.
Definition: hfl110dcu.h:298
uint8_t col_
Definition: hfl110dcu.h:280
ros::Publisher pub_points_
Pointcloud publisher.
Definition: hfl110dcu.h:316
const float NO_RETURN_DISTANCES
Definition: hfl110dcu.h:68
Definition: camera_commander.h:56
HFL110DCU v1 ethernet extrinsics struct.
Definition: hfl110dcu.h:107
float_t extrinsic_horizontal
Definition: hfl110dcu.h:114
uint32_t status
Definition: hfl110dcu.h:116
float_t intrinsic_pitch
Definition: hfl110dcu.h:109
float_t extrinsic_distance
Definition: hfl110dcu.h:115
float_t intrinsic_yaw
Definition: hfl110dcu.h:108
float_t extrinsic_pitch
Definition: hfl110dcu.h:111
float_t extrinsic_roll
Definition: hfl110dcu.h:112
float_t extrinsic_vertical
Definition: hfl110dcu.h:113
float_t extrinsic_yaw
Definition: hfl110dcu.h:110
HFL110DCU v1 ethernet extrinsics struct.
Definition: hfl110dcu.h:93
float_t t2
Definition: hfl110dcu.h:101
float_t fx
Definition: hfl110dcu.h:94
float_t r1
Definition: hfl110dcu.h:98
float_t t1
Definition: hfl110dcu.h:100
float_t uy
Definition: hfl110dcu.h:97
float_t ux
Definition: hfl110dcu.h:96
float_t r2
Definition: hfl110dcu.h:99
float_t r3
Definition: hfl110dcu.h:102
float_t fy
Definition: hfl110dcu.h:95
HFL110DCU v1 frame struct.
Definition: hfl110dcu.h:74
uint16_t range
Definition: hfl110dcu.h:75
uint16_t intensity
Definition: hfl110dcu.h:76
uint16_t intensity2
Definition: hfl110dcu.h:78
uint16_t range2
Definition: hfl110dcu.h:77
HFL110DCU v1 ethernet frame struct.
Definition: hfl110dcu.h:121
CameraExtrinsics camera_extrinsics
Definition: hfl110dcu.h:124
CameraIntrinsics camera_intrinsics
Definition: hfl110dcu.h:123
PointCloudReturn returns[128]
Definition: hfl110dcu.h:125
uint8_t pixel_type[128]
Definition: hfl110dcu.h:126
UdpPacketHeader header
Definition: hfl110dcu.h:122
HFL110DCU v1 ethernet packet header struct.
Definition: hfl110dcu.h:83
uint32_t upd_packet_number
Definition: hfl110dcu.h:87
uint16_t udp_version
Definition: hfl110dcu.h:84
uint64_t timeStamp
Definition: hfl110dcu.h:86
uint32_t image_row_number
Definition: hfl110dcu.h:88
uint16_t pca_version
Definition: hfl110dcu.h:85
HFL110DCU v1 ethernet object struct.
Definition: hfl110dcu.h:196
uint8_t confidence
Definition: hfl110dcu.h:203
uint8_t classification
Definition: hfl110dcu.h:202
objDyn dynamic_props
Definition: hfl110dcu.h:200
objGeo geometry
Definition: hfl110dcu.h:197
uint8_t quality
Definition: hfl110dcu.h:201
objKin kinematics
Definition: hfl110dcu.h:198
objState state
Definition: hfl110dcu.h:199
HFL110DCU v1 object dynamic property.
Definition: hfl110dcu.h:183
unsigned EM_GEN_OBJECT_DYN_PROPERTY_STOPPED
Definition: hfl110dcu.h:190
unsigned EM_GEN_OBJECT_DYN_PROPERTY_MOVING
Definition: hfl110dcu.h:184
unsigned EM_GEN_OBJECT_DYN_PROPERTY_CROSSING_RIGHT
Definition: hfl110dcu.h:188
unsigned EM_GEN_OBJECT_DYN_PROPERTY_ONCOMING
Definition: hfl110dcu.h:186
unsigned EM_GEN_OBJECT_DYN_PROPERTY_CROSSING_LEFT
Definition: hfl110dcu.h:187
unsigned EM_GEN_OBJECT_DYN_PROPERTY_UNKNOWN
Definition: hfl110dcu.h:189
unsigned EM_GEN_OBJECT_DYN_PROPERTY_MAX_DIFF_TYPES
Definition: hfl110dcu.h:191
unsigned EM_GEN_OBJECT_DYN_PROPERTY_STATIONARY
Definition: hfl110dcu.h:185
HFL110DCU v1 object geometry.
Definition: hfl110dcu.h:131
float x_rear_r
Definition: hfl110dcu.h:132
float x_front_l
Definition: hfl110dcu.h:136
float y_front_l
Definition: hfl110dcu.h:137
float y_rear_r
Definition: hfl110dcu.h:133
float x_rear_l
Definition: hfl110dcu.h:134
float y_rear_l
Definition: hfl110dcu.h:135
float fDistX
Definition: hfl110dcu.h:140
float yaw
Definition: hfl110dcu.h:142
float ground_offset
Definition: hfl110dcu.h:139
float fDistY
Definition: hfl110dcu.h:141
float height
Definition: hfl110dcu.h:138
HFL110DCU v1 object kinematics.
Definition: hfl110dcu.h:147
float fDistYVy
Definition: hfl110dcu.h:159
float fVyAx
Definition: hfl110dcu.h:165
float fDistXDistY
Definition: hfl110dcu.h:153
float fDistYAx
Definition: hfl110dcu.h:160
float fDistXVy
Definition: hfl110dcu.h:155
float fVxVy
Definition: hfl110dcu.h:162
float fVyAy
Definition: hfl110dcu.h:166
float fDistYAy
Definition: hfl110dcu.h:161
float fDistXVx
Definition: hfl110dcu.h:154
float fDistXAy
Definition: hfl110dcu.h:157
float fVrelX
Definition: hfl110dcu.h:150
float fVabsX
Definition: hfl110dcu.h:148
float fVxAx
Definition: hfl110dcu.h:163
float fDistXAx
Definition: hfl110dcu.h:156
float fDistYVx
Definition: hfl110dcu.h:158
float fVxAy
Definition: hfl110dcu.h:164
float fAxAy
Definition: hfl110dcu.h:167
float fVabsY
Definition: hfl110dcu.h:149
float fAabsX
Definition: hfl110dcu.h:152
float fVrelY
Definition: hfl110dcu.h:151
HFL110DCU v1 object state.
Definition: hfl110dcu.h:172
unsigned TP_OBJ_MT_STATE_MEASURED
Definition: hfl110dcu.h:175
unsigned TP_OBJ_MT_STATE_DELETED
Definition: hfl110dcu.h:173
unsigned TP_OBJ_MT_STATE_PREDICTED
Definition: hfl110dcu.h:176
unsigned TP_OBJ_MT_STATE_MAX_DIFF
Definition: hfl110dcu.h:178
unsigned TP_OBJ_MT_STATE_NEW
Definition: hfl110dcu.h:174
unsigned TP_OBJ_MT_STATE_INACTIVE
Definition: hfl110dcu.h:177