Classes | |
| class | BaseHFL110DCU |
| Base class for the HFL110DCU cameras. More... | |
| class | CameraCommander |
| Implements the camera configuration and setup. More... | |
| struct | CameraExtrinsics |
| HFL110DCU v1 ethernet extrinsics struct. More... | |
| struct | CameraIntrinsics |
| HFL110DCU v1 ethernet extrinsics struct. More... | |
| class | Frame |
| Handles camera's frame data. More... | |
| class | HFL110DCU |
| Implements the HFL110DCU camera image parsing and publishing. More... | |
| class | HflInterface |
| Base class for all of the HFL cameras. More... | |
| struct | hflObj |
| HFL110DCU v1 ethernet object struct. More... | |
| struct | objDyn |
| HFL110DCU v1 object dynamic property. More... | |
| struct | objGeo |
| HFL110DCU v1 object geometry. More... | |
| struct | objKin |
| HFL110DCU v1 object kinematics. More... | |
| struct | objState |
| HFL110DCU v1 object state. More... | |
| class | Pixel |
| Storages and handles the pixel data component. More... | |
| struct | PixelReturn |
| Data structure for pixel returns. More... | |
| struct | PointCloudReturn |
| HFL110DCU v1 frame struct. More... | |
| struct | telemetry |
| HFL110DCU v1 telemetry struct. More... | |
| struct | UdpFrame |
| HFL110DCU v1 ethernet frame struct. More... | |
| struct | UdpPacketHeader |
| HFL110DCU v1 ethernet packet header struct. More... | |
Typedefs | |
| using | Attribs_map = std::map< std::string, float > |
| Mode parameters map. More... | |
| using | Col = uint16_t |
| Column number data type. More... | |
| using | Configs_map = std::map< std::string, Attribs_map > |
| Camera modes map. More... | |
| using | Registers_map = std::map< std::string, Regs_bits_vec > |
| Cameras registers map. More... | |
| using | Regs_bits_vec = std::vector< std::pair< std::string, int >> |
| Register bit's values vector. More... | |
| using | Row = uint16_t |
| Row number data type. More... | |
| using | Setups_map = std::map< std::string, Configs_map > |
| HFL cameras map. More... | |
| using | Slice = std::vector< uint16_t > |
| Pixel's Slice data type. More... | |
Enumerations | |
| enum | commander_states { state_probe = 0, state_init, state_done, state_error } |
| Commander states enum. More... | |
| enum | error_codes { no_error = 0, frame_socket_error, pdm_socket_error, object_socket_error, tele_socket_error, slice_socket_error } |
| Error Codes. More... | |
| enum | num_bits { eight_bit = 0, ten_bit, twelve_bit, fourteen_bit } |
| Number of Bits. More... | |
| enum | udp_port_types { frame_data, object_data, lut_data } |
| UDP ports types. More... | |
Functions | |
| static float | big_to_native (float x) |
| static uint32_t | big_to_native (uint32_t x) |
| static uint16_t | big_to_native (uint16_t x) |
| static uint8_t | big_to_native (uint8_t x) |
Variables | |
| const char | CAMERA_INTRINSICS [] = "min000000" |
| Default camera intrinsics. More... | |
| const Setups_map | CAMERA_MODELS |
| HFL cameras memory maps and parameters. More... | |
| const uint32_t | EXPECTED_ADDRESS { 0xffffffff } |
| Default expected memory address. More... | |
| const uint16_t | FRAME_COLUMNS { 128 } |
| Default frame cols. More... | |
| const char | FRAME_ID [] = "hfl110dcu" |
| Default frame ID. More... | |
| const uint16_t | FRAME_ROWS { 32 } |
| Default frame rows. More... | |
| const uint8_t | INTENSITY_BITS { 13 } |
| Default bits used for intensity. More... | |
| const Registers_map | MODE_REGISTERS |
| HFL cameras mode registers. More... | |
| const uint16_t | PIXEL_RETURNS { 2 } |
| Default frame cols. More... | |
| const uint16_t | PIXEL_SLICES { 128 } |
| Default frame cols. More... | |
| const uint8_t | RANGE_BITS { 16 } |
| Default bits used for range. More... | |
| const Configs_map | REGS_OFFSET_ADDRS |
| HFL cameras register addresses. More... | |
| using hfl::Attribs_map = typedef std::map<std::string, float> |
Mode parameters map.
Definition at line 50 of file hfl_configs.h.
| using hfl::Col = typedef uint16_t |
Column number data type.
Definition at line 50 of file hfl_frame.h.
| using hfl::Configs_map = typedef std::map<std::string, Attribs_map> |
Camera modes map.
Definition at line 53 of file hfl_configs.h.
| using hfl::Registers_map = typedef std::map<std::string, Regs_bits_vec> |
Cameras registers map.
Definition at line 62 of file hfl_configs.h.
| using hfl::Regs_bits_vec = typedef std::vector<std::pair<std::string, int>> |
Register bit's values vector.
Definition at line 59 of file hfl_configs.h.
| using hfl::Row = typedef uint16_t |
Row number data type.
Definition at line 47 of file hfl_frame.h.
| using hfl::Setups_map = typedef std::map<std::string, Configs_map> |
HFL cameras map.
Definition at line 56 of file hfl_configs.h.
| using hfl::Slice = typedef std::vector<uint16_t> |
Pixel's Slice data type.
Definition at line 46 of file hfl_pixel.h.
Commander states enum.
| Enumerator | |
|---|---|
| state_probe | |
| state_init | |
| state_done | |
| state_error | |
Definition at line 58 of file camera_commander.h.
| enum hfl::error_codes |
Error Codes.
| Enumerator | |
|---|---|
| no_error | |
| frame_socket_error | |
| pdm_socket_error | |
| object_socket_error | |
| tele_socket_error | |
| slice_socket_error | |
Definition at line 67 of file camera_commander.h.
| enum hfl::num_bits |
Number of Bits.
| Enumerator | |
|---|---|
| eight_bit | |
| ten_bit | |
| twelve_bit | |
| fourteen_bit | |
Definition at line 84 of file hfl_interface.h.
| enum hfl::udp_port_types |
UDP ports types.
| Enumerator | |
|---|---|
| frame_data | |
| object_data | |
| lut_data | |
Definition at line 76 of file hfl_interface.h.
|
inlinestatic |
Definition at line 55 of file hfl_interface.h.
|
inlinestatic |
Definition at line 60 of file hfl_interface.h.
|
inlinestatic |
Definition at line 65 of file hfl_interface.h.
|
inlinestatic |
Definition at line 70 of file hfl_interface.h.
| const char hfl::CAMERA_INTRINSICS[] = "min000000" |
Default camera intrinsics.
Definition at line 59 of file base_hfl110dcu.h.
| const Setups_map hfl::CAMERA_MODELS |
HFL cameras memory maps and parameters.
Definition at line 71 of file hfl_configs.h.
| const uint32_t hfl::EXPECTED_ADDRESS { 0xffffffff } |
Default expected memory address.
Definition at line 61 of file base_hfl110dcu.h.
| const uint16_t hfl::FRAME_COLUMNS { 128 } |
Default frame cols.
Definition at line 47 of file base_hfl110dcu.h.
| const char hfl::FRAME_ID[] = "hfl110dcu" |
Default frame ID.
Definition at line 57 of file base_hfl110dcu.h.
| const uint16_t hfl::FRAME_ROWS { 32 } |
Default frame rows.
Definition at line 45 of file base_hfl110dcu.h.
| const uint8_t hfl::INTENSITY_BITS { 13 } |
Default bits used for intensity.
Definition at line 53 of file base_hfl110dcu.h.
| const Registers_map hfl::MODE_REGISTERS |
HFL cameras mode registers.
Definition at line 86 of file hfl_configs.h.
| const uint16_t hfl::PIXEL_RETURNS { 2 } |
Default frame cols.
Definition at line 49 of file base_hfl110dcu.h.
| const uint16_t hfl::PIXEL_SLICES { 128 } |
Default frame cols.
Definition at line 51 of file base_hfl110dcu.h.
| const uint8_t hfl::RANGE_BITS { 16 } |
Default bits used for range.
Definition at line 55 of file base_hfl110dcu.h.
| const Configs_map hfl::REGS_OFFSET_ADDRS |
HFL cameras register addresses.
Definition at line 66 of file hfl_configs.h.