hfl_driver  0.0.20
ROS driver for Continental's HFL110 3D Flash Lidar
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]
Collaboration diagram for hfl::HFL110DCU:
Collaboration graph
[legend]

Public Member Functions

 HFL110DCU (std::string model, std::string version, std::string frame_id, ros::NodeHandle &node_handler)
 
bool parseFrame (int start_byte, const std::vector< uint8_t > &packet) override
 
bool processFrameData (const std::vector< uint8_t > &data) override
 
bool parseObjects (int start_byte, const std::vector< uint8_t > &packet) override
 
bool processObjectData (const std::vector< uint8_t > &data) override
 
cv::Mat initTransform (cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial)
 
- Public Member Functions inherited from hfl::BaseHFL110DCU
bool setFrameRate (double rate) override
 
double getFrameRate (bool reg_format=false) const
 
bool setGlobalRangeOffset (double offset)
 
bool setChannelRangeOffset (uint8_t ch, double offset)
 
virtual bool setIntensityRangeOffset (uint8_t band, double offset)
 
- Public Member Functions inherited from hfl::HflInterface
std::string getModel () const
 
std::string getVersion () const
 
std::shared_ptr< Frameframe ()
 

Private Attributes

ros::NodeHandle node_handler_
 ROS node handler. More...
 
int bytes_received_
 Received packet bytes from HFL110. More...
 
std::shared_ptr< std_msgs::Header > frame_header_message_
 Frame Header message. More...
 
std::shared_ptr< std_msgs::Header > object_header_message_
 Object Header message. More...
 
std::shared_ptr< std_msgs::Header > tf_header_message_
 TF Header message. More...
 
uint8_t row_
 Row and column Counter. More...
 
uint8_t col_
 
uint8_t expected_packet_ = 0
 Return counter. More...
 
float focal_length_
 Focal Length. More...
 
camera_info_manager::CameraInfoManager * camera_info_manager_
 
cv_bridge::CvImagePtr p_image_depth_
 Pointer to depth image. More...
 
cv_bridge::CvImagePtr p_image_intensity_
 Pointer to 16 bit intensity image. More...
 
image_transport::CameraPublisher pub_depth_
 Depth image publisher. More...
 
image_transport::CameraPublisher pub_depth2_
 Depth image publisher second return 2. More...
 
image_transport::CameraPublisher pub_intensity_
 16 bit Intensity image publisher More...
 
image_transport::CameraPublisher pub_intensity2_
 16 bit Intensity image publisher return 2 More...
 
ros::Publisher pub_objects_
 Objects publisher. More...
 
std::vector< hflObjobjects_
 Objects vector;. More...
 
ros::Publisher pub_points_
 Pointcloud publisher. More...
 
std::shared_ptr< sensor_msgs::PointCloud2 > pointcloud_
 Pointcloud msg. More...
 
geometry_msgs::TransformStamped global_tf_
 ROS Transform. More...
 
cv::Mat transform_
 Transform. More...
 
cv_bridge::CvImagePtr p_image_depth2_
 Pointer to depth image second return. More...
 
cv_bridge::CvImagePtr p_image_intensity2_
 Pointer to 16 bit intensity image second return. More...
 

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
double range_magic_number_
 Range Magic Number. More...
 
Attribs_map mode_parameters
 Current mode parameters. More...
 
std::function< void(const std::vector< uint8_t > &)> udp_send_function_
 UDP sender function. More...
 
- Protected Attributes inherited from hfl::HflInterface
std::string model_
 Current camera model. More...
 
std::string version_
 Current camera model. More...
 
std::string ip_address_
 Camera's IP address. More...
 
uint16_t frame_data_port_
 Camera's UDP frame data port. More...
 
bool publish_tf_
 Current publish tf state. More...
 
std::string parent_frame_
 current static tf values More...
 
double x_
 
double y_
 
double z_
 
double roll_
 
double pitch_
 
double yaw_
 
double time_offset_
 time offset More...
 
double global_offset_
 global range offset More...
 
double ch1_offset_
 channel range offset More...
 
double ch2_offset_
 
double ch3_offset_
 
double ch4_offset_
 
double int500_offset_
 intensity range offset More...
 
double int1000_offset_
 
double int1500_offset_
 
double int2000_offset_
 
double int2500_offset_
 
double int3000_offset_
 
double int3500_offset_
 
double int4096_offset_
 
std::shared_ptr< hfl::Frameframe_
 Camera's frame configurations. More...
 

Detailed Description

Implements the HFL110DCU camera image parsing and publishing.

Constructor & Destructor Documentation

◆ HFL110DCU()

hfl::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

Member Function Documentation

◆ initTransform()

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

◆ parseFrame()

bool hfl::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.

◆ parseObjects()

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

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.

◆ processFrameData()

bool hfl::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.

◆ processObjectData()

bool hfl::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.

Member Data Documentation

◆ bytes_received_

int hfl::HFL110DCU::bytes_received_
private

Received packet bytes from HFL110.

◆ camera_info_manager_

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

◆ col_

uint8_t hfl::HFL110DCU::col_
private

◆ expected_packet_

uint8_t hfl::HFL110DCU::expected_packet_ = 0
private

Return counter.

◆ focal_length_

float hfl::HFL110DCU::focal_length_
private

Focal Length.

◆ frame_header_message_

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

Frame Header message.

◆ global_tf_

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

ROS Transform.

◆ node_handler_

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

ROS node handler.

◆ object_header_message_

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

Object Header message.

◆ objects_

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

Objects vector;.

◆ p_image_depth2_

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

Pointer to depth image second return.

◆ p_image_depth_

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

Pointer to depth image.

◆ p_image_intensity2_

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

Pointer to 16 bit intensity image second return.

◆ p_image_intensity_

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

Pointer to 16 bit intensity image.

◆ pointcloud_

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

Pointcloud msg.

◆ pub_depth2_

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

Depth image publisher second return 2.

◆ pub_depth_

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

Depth image publisher.

◆ pub_intensity2_

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

16 bit Intensity image publisher return 2

◆ pub_intensity_

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

16 bit Intensity image publisher

◆ pub_objects_

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

Objects publisher.

◆ pub_points_

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

Pointcloud publisher.

◆ row_

uint8_t hfl::HFL110DCU::row_
private

Row and column Counter.

◆ tf_header_message_

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

TF Header message.

◆ transform_

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

Transform.


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