Public Member Functions | Private Attributes | List of all members
hfl::HFL110DCU Class Reference

Implements the HFL110DCU camera image parsing and publishing. More...

#include <hfl110dcu.h>

Inheritance diagram for hfl::HFL110DCU:
Inheritance graph
[legend]

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< Frameframe ()
 
std::string getModel () const
 
std::string getVersion () const
 

Private Attributes

int bytes_received_
 Received packet bytes from HFL110. More...
 
camera_info_manager::CameraInfoManagercamera_info_manager_
 
uint8_t col_
 
uint8_t expected_packet_ = 0
 Return counter. More...
 
float focal_length_
 Focal Length. More...
 
std::shared_ptr< std_msgs::Headerframe_header_message_
 Frame Header message. More...
 
geometry_msgs::TransformStamped global_tf_
 ROS Transform. More...
 
ros::NodeHandle node_handler_
 ROS node handler. More...
 
std::shared_ptr< std_msgs::Headerobject_header_message_
 Object Header message. More...
 
std::vector< hflObjobjects_
 Objects vector;. More...
 
cv_bridge::CvImagePtr p_image_crosstalk2_
 Pointer to crosstalk2 flags. More...
 
cv_bridge::CvImagePtr p_image_crosstalk_
 Pointer to crosstalk flags. More...
 
cv_bridge::CvImagePtr p_image_depth2_
 Pointer to depth image second return. More...
 
cv_bridge::CvImagePtr p_image_depth_
 Pointer to depth image. More...
 
cv_bridge::CvImagePtr p_image_intensity2_
 Pointer to 16 bit intensity image second return. More...
 
cv_bridge::CvImagePtr p_image_intensity_
 Pointer to 16 bit intensity image. More...
 
cv_bridge::CvImagePtr p_image_saturated2_
 Pointer to saturated2 flags. More...
 
cv_bridge::CvImagePtr p_image_saturated_
 Pointer to saturated flags. More...
 
cv_bridge::CvImagePtr p_image_superimposed2_
 Pointer to superimposed2 flags. More...
 
cv_bridge::CvImagePtr p_image_superimposed_
 Pointer to superimposed flags. More...
 
std::shared_ptr< std_msgs::Headerpdm_header_message_
 PDM Header message. More...
 
std::shared_ptr< sensor_msgs::PointCloud2 > pointcloud_
 Pointcloud msg. More...
 
image_transport::CameraPublisher pub_ct2_
 Crosstalk2 flag image publisher. More...
 
image_transport::CameraPublisher pub_ct_
 Crosstalk flag image publisher. More...
 
image_transport::CameraPublisher pub_depth2_
 Depth image publisher second return 2. More...
 
image_transport::CameraPublisher pub_depth_
 Depth image publisher. More...
 
image_transport::CameraPublisher pub_intensity2_
 16 bit Intensity image publisher return 2 More...
 
image_transport::CameraPublisher pub_intensity_
 16 bit Intensity image publisher More...
 
ros::Publisher pub_objects_
 Objects publisher. More...
 
ros::Publisher pub_points_
 Pointcloud publisher. More...
 
image_transport::CameraPublisher pub_sat2_
 Saturated2 flag image publisher. More...
 
image_transport::CameraPublisher pub_sat_
 Saturated flag image publisher. More...
 
image_transport::CameraPublisher pub_si2_
 Superimposed flag image publisher. More...
 
image_transport::CameraPublisher pub_si_
 Superimposed flag image publisher. More...
 
ros::Publisher pub_slices_
 Slices publisher. More...
 
uint8_t row_
 Row and column Counter. More...
 
std::shared_ptr< std_msgs::Headerslice_header_message_
 Slice Header message. More...
 
std::shared_ptr< std_msgs::UInt16MultiArray > slices_
 Slices msg. More...
 
std::shared_ptr< std_msgs::Headertele_header_message_
 Telemetry Header message. More...
 
telemetry telem_ {}
 Telemetry Data. More...
 
std::shared_ptr< std_msgs::Headertf_header_message_
 TF Header message. More...
 
cv::Mat transform_
 Transform. More...
 
diagnostic_updater::Updater updater_
 

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::Frameframe_
 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_
 

Detailed Description

Implements the HFL110DCU camera image parsing and publishing.

Definition at line 229 of file hfl110dcu.h.

Constructor & Destructor Documentation

HFL110DCU::HFL110DCU ( std::string  model,
std::string  version,
std::string  frame_id,
ros::NodeHandle node_handler 
)

HFL110DCU image processor constructor.

Parameters
[in]modelcamera hfl model
[in]versioncamera version
[in]frame_idcamera's coordinate frame name
[in]node_handlerreference to the ros node handler

Definition at line 52 of file hfl110dcu.cpp.

Member Function Documentation

cv::Mat HFL110DCU::initTransform ( cv::Mat  cameraMatrix,
cv::Mat  distCoeffs,
int  width,
int  height,
bool  radial 
)

Definition at line 723 of file hfl110dcu.cpp.

bool HFL110DCU::parseFrame ( int  start_byte,
const std::vector< uint8_t > &  packet 
)
overridevirtual

Parse out the packet data into depth and intensity images

Parameters
[in]startingbyte, packet to parse
Returns
bool true if successfully parsed packet

Implements hfl::HflInterface.

Definition at line 133 of file hfl110dcu.cpp.

bool HFL110DCU::parseObjects ( int  start_byte,
const std::vector< uint8_t > &  packet 
)
overridevirtual

Parse out pdm data from packet

Parameters
[in]startingbyte, packet to parse
Returns
bool true if successfully parsed packet Process performance degredation module (PDM) data from udp packets.
Parameters
[in]datapdm data array
Returns
bool true if successful Parse packet into objects
Parameters
[in]start_bytestarting byte, packet packet data to parse
Returns
bool true if successfully parsed object data

Implements hfl::BaseHFL110DCU.

Definition at line 484 of file hfl110dcu.cpp.

bool HFL110DCU::processFrameData ( const std::vector< uint8_t > &  data)
overridevirtual

Process data frame from udp packets.

Parameters
[in]dataframe data array
Returns
bool true if successful

Implements hfl::HflInterface.

Definition at line 197 of file hfl110dcu.cpp.

bool HFL110DCU::processObjectData ( const std::vector< uint8_t > &  data)
overridevirtual

Process the object data from udp packets

Parameters
[in]dataobject data
Returns
bool

Implements hfl::BaseHFL110DCU.

Definition at line 550 of file hfl110dcu.cpp.

bool HFL110DCU::processSliceData ( const std::vector< uint8_t > &  data)
overridevirtual

Process the slice data from udp packets

Parameters
[in]dataslice data
Returns
bool

Implements hfl::BaseHFL110DCU.

Definition at line 717 of file hfl110dcu.cpp.

bool HFL110DCU::processTelemetryData ( const std::vector< uint8_t > &  data)
overridevirtual

Process the telemetry data from udp packets

Parameters
[in]datatelemetry data
Returns
bool

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.

Member Data Documentation

int hfl::HFL110DCU::bytes_received_
private

Received packet bytes from HFL110.

Definition at line 327 of file hfl110dcu.h.

camera_info_manager::CameraInfoManager* hfl::HFL110DCU::camera_info_manager_
private

Definition at line 357 of file hfl110dcu.h.

uint8_t hfl::HFL110DCU::col_
private

Definition at line 348 of file hfl110dcu.h.

uint8_t hfl::HFL110DCU::expected_packet_ = 0
private

Return counter.

Definition at line 351 of file hfl110dcu.h.

float hfl::HFL110DCU::focal_length_
private

Focal Length.

Definition at line 354 of file hfl110dcu.h.

std::shared_ptr<std_msgs::Header> hfl::HFL110DCU::frame_header_message_
private

Frame Header message.

Definition at line 330 of file hfl110dcu.h.

geometry_msgs::TransformStamped hfl::HFL110DCU::global_tf_
private

ROS Transform.

Definition at line 441 of file hfl110dcu.h.

ros::NodeHandle hfl::HFL110DCU::node_handler_
private

ROS node handler.

Definition at line 324 of file hfl110dcu.h.

std::shared_ptr<std_msgs::Header> hfl::HFL110DCU::object_header_message_
private

Object Header message.

Definition at line 336 of file hfl110dcu.h.

std::vector<hflObj> hfl::HFL110DCU::objects_
private

Objects vector;.

Definition at line 426 of file hfl110dcu.h.

cv_bridge::CvImagePtr hfl::HFL110DCU::p_image_crosstalk2_
private

Pointer to crosstalk2 flags.

Definition at line 381 of file hfl110dcu.h.

cv_bridge::CvImagePtr hfl::HFL110DCU::p_image_crosstalk_
private

Pointer to crosstalk flags.

Definition at line 372 of file hfl110dcu.h.

cv_bridge::CvImagePtr hfl::HFL110DCU::p_image_depth2_
private

Pointer to depth image second return.

Definition at line 366 of file hfl110dcu.h.

cv_bridge::CvImagePtr hfl::HFL110DCU::p_image_depth_
private

Pointer to depth image.

Definition at line 360 of file hfl110dcu.h.

cv_bridge::CvImagePtr hfl::HFL110DCU::p_image_intensity2_
private

Pointer to 16 bit intensity image second return.

Definition at line 369 of file hfl110dcu.h.

cv_bridge::CvImagePtr hfl::HFL110DCU::p_image_intensity_
private

Pointer to 16 bit intensity image.

Definition at line 363 of file hfl110dcu.h.

cv_bridge::CvImagePtr hfl::HFL110DCU::p_image_saturated2_
private

Pointer to saturated2 flags.

Definition at line 384 of file hfl110dcu.h.

cv_bridge::CvImagePtr hfl::HFL110DCU::p_image_saturated_
private

Pointer to saturated flags.

Definition at line 375 of file hfl110dcu.h.

cv_bridge::CvImagePtr hfl::HFL110DCU::p_image_superimposed2_
private

Pointer to superimposed2 flags.

Definition at line 387 of file hfl110dcu.h.

cv_bridge::CvImagePtr hfl::HFL110DCU::p_image_superimposed_
private

Pointer to superimposed flags.

Definition at line 378 of file hfl110dcu.h.

std::shared_ptr<std_msgs::Header> hfl::HFL110DCU::pdm_header_message_
private

PDM Header message.

Definition at line 333 of file hfl110dcu.h.

std::shared_ptr<sensor_msgs::PointCloud2> hfl::HFL110DCU::pointcloud_
private

Pointcloud msg.

Definition at line 435 of file hfl110dcu.h.

image_transport::CameraPublisher hfl::HFL110DCU::pub_ct2_
private

Crosstalk2 flag image publisher.

Definition at line 405 of file hfl110dcu.h.

image_transport::CameraPublisher hfl::HFL110DCU::pub_ct_
private

Crosstalk flag image publisher.

Definition at line 402 of file hfl110dcu.h.

image_transport::CameraPublisher hfl::HFL110DCU::pub_depth2_
private

Depth image publisher second return 2.

Definition at line 393 of file hfl110dcu.h.

image_transport::CameraPublisher hfl::HFL110DCU::pub_depth_
private

Depth image publisher.

Definition at line 390 of file hfl110dcu.h.

image_transport::CameraPublisher hfl::HFL110DCU::pub_intensity2_
private

16 bit Intensity image publisher return 2

Definition at line 399 of file hfl110dcu.h.

image_transport::CameraPublisher hfl::HFL110DCU::pub_intensity_
private

16 bit Intensity image publisher

Definition at line 396 of file hfl110dcu.h.

ros::Publisher hfl::HFL110DCU::pub_objects_
private

Objects publisher.

Definition at line 420 of file hfl110dcu.h.

ros::Publisher hfl::HFL110DCU::pub_points_
private

Pointcloud publisher.

Definition at line 429 of file hfl110dcu.h.

image_transport::CameraPublisher hfl::HFL110DCU::pub_sat2_
private

Saturated2 flag image publisher.

Definition at line 411 of file hfl110dcu.h.

image_transport::CameraPublisher hfl::HFL110DCU::pub_sat_
private

Saturated flag image publisher.

Definition at line 408 of file hfl110dcu.h.

image_transport::CameraPublisher hfl::HFL110DCU::pub_si2_
private

Superimposed flag image publisher.

Definition at line 417 of file hfl110dcu.h.

image_transport::CameraPublisher hfl::HFL110DCU::pub_si_
private

Superimposed flag image publisher.

Definition at line 414 of file hfl110dcu.h.

ros::Publisher hfl::HFL110DCU::pub_slices_
private

Slices publisher.

Definition at line 423 of file hfl110dcu.h.

uint8_t hfl::HFL110DCU::row_
private

Row and column Counter.

Definition at line 348 of file hfl110dcu.h.

std::shared_ptr<std_msgs::Header> hfl::HFL110DCU::slice_header_message_
private

Slice Header message.

Definition at line 342 of file hfl110dcu.h.

std::shared_ptr<std_msgs::UInt16MultiArray> hfl::HFL110DCU::slices_
private

Slices msg.

Definition at line 438 of file hfl110dcu.h.

std::shared_ptr<std_msgs::Header> hfl::HFL110DCU::tele_header_message_
private

Telemetry Header message.

Definition at line 339 of file hfl110dcu.h.

telemetry hfl::HFL110DCU::telem_ {}
private

Telemetry Data.

Definition at line 432 of file hfl110dcu.h.

std::shared_ptr<std_msgs::Header> hfl::HFL110DCU::tf_header_message_
private

TF Header message.

Definition at line 345 of file hfl110dcu.h.

cv::Mat hfl::HFL110DCU::transform_
private

Transform.

Definition at line 444 of file hfl110dcu.h.

diagnostic_updater::Updater hfl::HFL110DCU::updater_
private

Definition at line 447 of file hfl110dcu.h.


The documentation for this class was generated from the following files:


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