Implements the HFL110DCU camera image parsing and publishing. More...
#include <hfl110dcu.h>

Public Member Functions | |
| HFL110DCU (std::string model, std::string version, std::string frame_id, ros::NodeHandle &node_handler) | |
| cv::Mat | initTransform (cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial) |
| bool | parseFrame (int start_byte, const std::vector< uint8_t > &packet) override |
| bool | parseObjects (int start_byte, const std::vector< uint8_t > &packet) override |
| bool | processFrameData (const std::vector< uint8_t > &data) override |
| bool | processObjectData (const std::vector< uint8_t > &data) override |
| bool | processSliceData (const std::vector< uint8_t > &data) override |
| bool | processTelemetryData (const std::vector< uint8_t > &data) override |
| void | update_diagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Public Member Functions inherited from hfl::BaseHFL110DCU | |
| double | getFrameRate (bool reg_format=false) const |
| bool | setFrameRate (double rate) override |
| bool | setGlobalRangeOffset (double offset) |
Public Member Functions inherited from hfl::HflInterface | |
| std::shared_ptr< Frame > | frame () |
| std::string | getModel () const |
| std::string | getVersion () const |
Additional Inherited Members | |
Protected Types inherited from hfl::BaseHFL110DCU | |
| enum | HFL110DCU_memory_types { mem_ri = 0, types_size } |
| HFL110DCU camera memory_types. More... | |
Protected Member Functions inherited from hfl::BaseHFL110DCU | |
| bool | getConfiguration (std::string model, std::string version) |
Protected Attributes inherited from hfl::BaseHFL110DCU | |
| Attribs_map | mode_parameters |
| Current mode parameters. More... | |
| double | range_magic_number_ |
| Range Magic Number. More... | |
| std::function< void(const std::vector< uint8_t > &)> | udp_send_function_ |
| UDP sender function. More... | |
Protected Attributes inherited from hfl::HflInterface | |
| std::shared_ptr< hfl::Frame > | frame_ |
| Camera's frame configurations. More... | |
| uint16_t | frame_data_port_ |
| Camera's UDP frame data port. More... | |
| double | global_offset_ |
| global range offset More... | |
| std::string | ip_address_ |
| Camera's IP address. More... | |
| std::string | model_ |
| Current camera model. More... | |
| std::string | parent_frame_ |
| current static tf values More... | |
| double | pitch_ |
| bool | publish_tf_ |
| Current publish tf state. More... | |
| double | roll_ |
| double | time_offset_ |
| time offset More... | |
| std::string | version_ |
| Current camera model. More... | |
| double | x_ |
| double | y_ |
| double | yaw_ |
| double | z_ |
Implements the HFL110DCU camera image parsing and publishing.
Definition at line 229 of file hfl110dcu.h.
| HFL110DCU::HFL110DCU | ( | std::string | model, |
| std::string | version, | ||
| std::string | frame_id, | ||
| ros::NodeHandle & | node_handler | ||
| ) |
HFL110DCU image processor constructor.
| [in] | model | camera hfl model |
| [in] | version | camera version |
| [in] | frame_id | camera's coordinate frame name |
| [in] | node_handler | reference to the ros node handler |
Definition at line 52 of file hfl110dcu.cpp.
| cv::Mat HFL110DCU::initTransform | ( | cv::Mat | cameraMatrix, |
| cv::Mat | distCoeffs, | ||
| int | width, | ||
| int | height, | ||
| bool | radial | ||
| ) |
Definition at line 723 of file hfl110dcu.cpp.
|
overridevirtual |
Parse out the packet data into depth and intensity images
| [in] | starting | byte, packet to parse |
Implements hfl::HflInterface.
Definition at line 133 of file hfl110dcu.cpp.
|
overridevirtual |
Parse out pdm data from packet
| [in] | starting | byte, packet to parse |
| [in] | data | pdm data array |
| [in] | start_byte | starting byte, packet packet data to parse |
Implements hfl::BaseHFL110DCU.
Definition at line 484 of file hfl110dcu.cpp.
|
overridevirtual |
Process data frame from udp packets.
| [in] | data | frame data array |
Implements hfl::HflInterface.
Definition at line 197 of file hfl110dcu.cpp.
|
overridevirtual |
Process the object data from udp packets
| [in] | data | object data |
Implements hfl::BaseHFL110DCU.
Definition at line 550 of file hfl110dcu.cpp.
|
overridevirtual |
Process the slice data from udp packets
| [in] | data | slice data |
Implements hfl::BaseHFL110DCU.
Definition at line 717 of file hfl110dcu.cpp.
|
overridevirtual |
Process the telemetry data from udp packets
| [in] | data | telemetry data |
Implements hfl::BaseHFL110DCU.
Definition at line 675 of file hfl110dcu.cpp.
| void HFL110DCU::update_diagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) |
Definition at line 765 of file hfl110dcu.cpp.
|
private |
Received packet bytes from HFL110.
Definition at line 327 of file hfl110dcu.h.
|
private |
Definition at line 357 of file hfl110dcu.h.
|
private |
Definition at line 348 of file hfl110dcu.h.
|
private |
Return counter.
Definition at line 351 of file hfl110dcu.h.
|
private |
Focal Length.
Definition at line 354 of file hfl110dcu.h.
|
private |
Definition at line 330 of file hfl110dcu.h.
|
private |
ROS Transform.
Definition at line 441 of file hfl110dcu.h.
|
private |
ROS node handler.
Definition at line 324 of file hfl110dcu.h.
|
private |
Object Header message.
Definition at line 336 of file hfl110dcu.h.
|
private |
Objects vector;.
Definition at line 426 of file hfl110dcu.h.
|
private |
Pointer to crosstalk2 flags.
Definition at line 381 of file hfl110dcu.h.
|
private |
Pointer to crosstalk flags.
Definition at line 372 of file hfl110dcu.h.
|
private |
Pointer to depth image second return.
Definition at line 366 of file hfl110dcu.h.
|
private |
Pointer to depth image.
Definition at line 360 of file hfl110dcu.h.
|
private |
Pointer to 16 bit intensity image second return.
Definition at line 369 of file hfl110dcu.h.
|
private |
Pointer to 16 bit intensity image.
Definition at line 363 of file hfl110dcu.h.
|
private |
Pointer to saturated2 flags.
Definition at line 384 of file hfl110dcu.h.
|
private |
Pointer to saturated flags.
Definition at line 375 of file hfl110dcu.h.
|
private |
Pointer to superimposed2 flags.
Definition at line 387 of file hfl110dcu.h.
|
private |
Pointer to superimposed flags.
Definition at line 378 of file hfl110dcu.h.
|
private |
PDM Header message.
Definition at line 333 of file hfl110dcu.h.
|
private |
Pointcloud msg.
Definition at line 435 of file hfl110dcu.h.
|
private |
Crosstalk2 flag image publisher.
Definition at line 405 of file hfl110dcu.h.
|
private |
Crosstalk flag image publisher.
Definition at line 402 of file hfl110dcu.h.
|
private |
Depth image publisher second return 2.
Definition at line 393 of file hfl110dcu.h.
|
private |
Depth image publisher.
Definition at line 390 of file hfl110dcu.h.
|
private |
16 bit Intensity image publisher return 2
Definition at line 399 of file hfl110dcu.h.
|
private |
16 bit Intensity image publisher
Definition at line 396 of file hfl110dcu.h.
|
private |
Objects publisher.
Definition at line 420 of file hfl110dcu.h.
|
private |
Pointcloud publisher.
Definition at line 429 of file hfl110dcu.h.
|
private |
Saturated2 flag image publisher.
Definition at line 411 of file hfl110dcu.h.
|
private |
Saturated flag image publisher.
Definition at line 408 of file hfl110dcu.h.
|
private |
Superimposed flag image publisher.
Definition at line 417 of file hfl110dcu.h.
|
private |
Superimposed flag image publisher.
Definition at line 414 of file hfl110dcu.h.
|
private |
Slices publisher.
Definition at line 423 of file hfl110dcu.h.
|
private |
Row and column Counter.
Definition at line 348 of file hfl110dcu.h.
|
private |
Slice Header message.
Definition at line 342 of file hfl110dcu.h.
|
private |
Slices msg.
Definition at line 438 of file hfl110dcu.h.
|
private |
Telemetry Header message.
Definition at line 339 of file hfl110dcu.h.
|
private |
Telemetry Data.
Definition at line 432 of file hfl110dcu.h.
|
private |
TF Header message.
Definition at line 345 of file hfl110dcu.h.
|
private |
Transform.
Definition at line 444 of file hfl110dcu.h.
|
private |
Definition at line 447 of file hfl110dcu.h.