base_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 BASE_HFL110DCU_H_
37 #define BASE_HFL110DCU_H_
38 #include <hfl_interface.h>
39 #include <string>
40 #include <vector>
41 
42 namespace hfl
43 {
45 const uint16_t FRAME_ROWS{ 32 };
47 const uint16_t FRAME_COLUMNS{ 128 };
49 const uint16_t PIXEL_RETURNS{ 2 };
51 const uint16_t PIXEL_SLICES{ 128 };
53 const uint8_t INTENSITY_BITS{ 13 };
55 const uint8_t RANGE_BITS{ 16 };
57 const char FRAME_ID[] = "hfl110dcu";
59 const char CAMERA_INTRINSICS[] = "min000000";
61 const uint32_t EXPECTED_ADDRESS{ 0xffffffff };
62 
67 {
68 public:
76  bool setFrameRate(double rate) override
77  {
78  return false;
79  }
80 
86  double getFrameRate(bool reg_format = false) const
87  {
88  return 25.0;
89  };
90 
98  bool setGlobalRangeOffset(double offset);
99 
100 protected:
103 
106 
108  std::function<void(const std::vector<uint8_t>&)> udp_send_function_;
109 
112  {
113  mem_ri = 0,
115  };
116 
126  bool getConfiguration(std::string model, std::string version);
127 
135  virtual bool parseObjects(int start_byte, const std::vector<uint8_t>& packet) = 0;
136 
144  virtual bool processObjectData(const std::vector<uint8_t>& data) = 0;
145 
153  virtual bool processTelemetryData(const std::vector<uint8_t>& data) = 0;
154 
162  virtual bool processSliceData(const std::vector<uint8_t>& data) = 0;
163 };
164 } // namespace hfl
165 
166 #endif // BASE_HFL110DCU_H_
const uint8_t RANGE_BITS
Default bits used for range.
double getFrameRate(bool reg_format=false) const
virtual bool processObjectData(const std::vector< uint8_t > &data)=0
bool getConfiguration(std::string model, std::string version)
const uint32_t EXPECTED_ADDRESS
Default expected memory address.
virtual bool parseObjects(int start_byte, const std::vector< uint8_t > &packet)=0
HFL110DCU_memory_types
HFL110DCU camera memory_types.
double range_magic_number_
Range Magic Number.
virtual bool processSliceData(const std::vector< uint8_t > &data)=0
virtual bool processTelemetryData(const std::vector< uint8_t > &data)=0
const uint16_t PIXEL_SLICES
Default frame cols.
const uint16_t FRAME_COLUMNS
Default frame cols.
std::function< void(const std::vector< uint8_t > &)> udp_send_function_
UDP sender function.
This file defines the HFL camera&#39;s interface class.
const uint16_t PIXEL_RETURNS
Default frame cols.
const char CAMERA_INTRINSICS[]
Default camera intrinsics.
const uint16_t FRAME_ROWS
Default frame rows.
bool setGlobalRangeOffset(double offset)
Base class for the HFL110DCU cameras.
const uint8_t INTENSITY_BITS
Default bits used for intensity.
std::map< std::string, float > Attribs_map
Mode parameters map.
Definition: hfl_configs.h:50
const char FRAME_ID[]
Default frame ID.
bool setFrameRate(double rate) override
Attribs_map mode_parameters
Current mode parameters.
Base class for all of the HFL cameras.
Definition: hfl_interface.h:95


hfl_driver
Author(s): Evan Flynn , Maxton Ginier , Gerardo Bravo , Moises Diaz
autogenerated on Sat Mar 20 2021 02:27:31