hfl_interface.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 
37 #ifndef HFL_INTERFACE_H_
38 #define HFL_INTERFACE_H_
39 #include <hfl_configs.h>
40 #include <hfl_frame.h>
41 
42 #ifdef _WIN32
43 #include <winsock2.h>
44 #elif __linux__
45 #include <arpa/inet.h> // ntohl()
46 #endif
47 
48 #include <string>
49 #include <vector>
50 #include <memory>
51 
52 namespace hfl
53 {
54 
55 static inline float big_to_native(float x)
56 {
57  return ntohl(x);
58 }
59 
60 static inline uint32_t big_to_native(uint32_t x)
61 {
62  return ntohl(x);
63 }
64 
65 static inline uint16_t big_to_native(uint16_t x)
66 {
67  return ntohs(x);
68 }
69 
70 static inline uint8_t big_to_native(uint8_t x)
71 {
72  return x;
73 }
74 
77 {
81 };
82 
85 {
86  eight_bit = 0,
90 };
91 
96 {
97 protected:
99  std::string model_;
100 
102  std::string version_;
103 
105  std::string ip_address_;
106 
109 
112 
114  std::string parent_frame_;
115  double x_;
116  double y_;
117  double z_;
118  double roll_;
119  double pitch_;
120  double yaw_;
121 
123  double time_offset_;
124 
127 
129  std::shared_ptr<hfl::Frame> frame_;
130 
131 public:
137  std::string getModel() const;
138 
144  std::string getVersion() const;
145 
153  virtual bool setFrameRate(double rate) = 0;
154 
161  virtual double getFrameRate(bool reg_format = false) const = 0;
162 
170  virtual bool setGlobalRangeOffset(double offset) = 0;
171 
179  virtual bool parseFrame(int start_byte, const std::vector<uint8_t>& packet) = 0;
180 
188  virtual bool processFrameData(const std::vector<uint8_t>& data) = 0;
189 
197  virtual bool parseObjects(int start_byte, const std::vector<uint8_t>& packet) = 0;
198 
206  virtual bool processObjectData(const std::vector<uint8_t>& data) = 0;
207 
215  virtual bool processTelemetryData(const std::vector<uint8_t>& data) = 0;
216 
224  virtual bool processSliceData(const std::vector<uint8_t>& data) = 0;
225 
231  std::shared_ptr<Frame> frame();
232 };
233 
234 } // namespace hfl
235 #endif // HFL_INTERFACE_H_
hfl::object_data
@ object_data
Definition: hfl_interface.h:79
hfl::HflInterface::parseFrame
virtual bool parseFrame(int start_byte, const std::vector< uint8_t > &packet)=0
hfl::HflInterface::parent_frame_
std::string parent_frame_
current static tf values
Definition: hfl_interface.h:114
hfl::HflInterface::global_offset_
double global_offset_
global range offset
Definition: hfl_interface.h:126
hfl::HflInterface::processObjectData
virtual bool processObjectData(const std::vector< uint8_t > &data)=0
hfl_configs.h
This file defines HFL cameras data and custom types.
hfl::num_bits
num_bits
Number of Bits.
Definition: hfl_interface.h:84
hfl::big_to_native
static float big_to_native(float x)
Definition: hfl_interface.h:55
hfl
Definition: base_hfl110dcu.h:42
hfl::udp_port_types
udp_port_types
UDP ports types.
Definition: hfl_interface.h:76
hfl::HflInterface::processFrameData
virtual bool processFrameData(const std::vector< uint8_t > &data)=0
hfl::HflInterface::processSliceData
virtual bool processSliceData(const std::vector< uint8_t > &data)=0
hfl::HflInterface::version_
std::string version_
Current camera model.
Definition: hfl_interface.h:102
hfl::HflInterface::getModel
std::string getModel() const
Definition: hfl_interface.cpp:47
hfl::HflInterface::setGlobalRangeOffset
virtual bool setGlobalRangeOffset(double offset)=0
hfl::HflInterface::y_
double y_
Definition: hfl_interface.h:116
hfl::HflInterface::getFrameRate
virtual double getFrameRate(bool reg_format=false) const =0
hfl::HflInterface::frame
std::shared_ptr< Frame > frame()
Definition: hfl_interface.cpp:57
hfl::HflInterface::x_
double x_
Definition: hfl_interface.h:115
hfl::twelve_bit
@ twelve_bit
Definition: hfl_interface.h:88
hfl::HflInterface::publish_tf_
bool publish_tf_
Current publish tf state.
Definition: hfl_interface.h:111
hfl::fourteen_bit
@ fourteen_bit
Definition: hfl_interface.h:89
hfl::HflInterface::frame_
std::shared_ptr< hfl::Frame > frame_
Camera's frame configurations.
Definition: hfl_interface.h:129
hfl::HflInterface::model_
std::string model_
Current camera model.
Definition: hfl_interface.h:99
hfl::HflInterface::ip_address_
std::string ip_address_
Camera's IP address.
Definition: hfl_interface.h:105
hfl::frame_data
@ frame_data
Definition: hfl_interface.h:78
hfl::HflInterface::parseObjects
virtual bool parseObjects(int start_byte, const std::vector< uint8_t > &packet)=0
hfl::lut_data
@ lut_data
Definition: hfl_interface.h:80
hfl::HflInterface::yaw_
double yaw_
Definition: hfl_interface.h:120
hfl::HflInterface::frame_data_port_
uint16_t frame_data_port_
Camera's UDP frame data port.
Definition: hfl_interface.h:108
hfl::HflInterface::pitch_
double pitch_
Definition: hfl_interface.h:119
hfl::ten_bit
@ ten_bit
Definition: hfl_interface.h:87
hfl::HflInterface::z_
double z_
Definition: hfl_interface.h:117
hfl::HflInterface
Base class for all of the HFL cameras.
Definition: hfl_interface.h:95
hfl::HflInterface::roll_
double roll_
Definition: hfl_interface.h:118
hfl::HflInterface::setFrameRate
virtual bool setFrameRate(double rate)=0
hfl::HflInterface::time_offset_
double time_offset_
time offset
Definition: hfl_interface.h:123
hfl_frame.h
This file defines the camera's Frame class.
hfl::eight_bit
@ eight_bit
Definition: hfl_interface.h:86
hfl::HflInterface::processTelemetryData
virtual bool processTelemetryData(const std::vector< uint8_t > &data)=0
hfl::HflInterface::getVersion
std::string getVersion() const
Definition: hfl_interface.cpp:52


hfl_driver
Author(s): Evan Flynn , Maxton Ginier , Gerardo Bravo , Moises Diaz
autogenerated on Wed Mar 2 2022 00:22:32