Implements the HFL110DCU camera image parsing and publishing.
More...
#include <hfl110dcu.h>
|
| | 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) |
| |
| 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) |
| |
| std::string | getModel () const |
| |
| std::string | getVersion () const |
| |
| std::shared_ptr< Frame > | frame () |
| |
Implements the HFL110DCU camera image parsing and publishing.
◆ HFL110DCU()
| hfl::HFL110DCU::HFL110DCU |
( |
std::string |
model, |
|
|
std::string |
version, |
|
|
std::string |
frame_id, |
|
|
ros::NodeHandle & |
node_handler |
|
) |
| |
HFL110DCU image processor constructor.
- Parameters
-
| [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 |
◆ 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] | starting | byte, 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_byte | starting 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
-
- 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
-
- Returns
- bool
Implements hfl::BaseHFL110DCU.
◆ 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 |
◆ focal_length_
| float hfl::HFL110DCU::focal_length_ |
|
private |
◆ frame_header_message_
| std::shared_ptr<std_msgs::Header> hfl::HFL110DCU::frame_header_message_ |
|
private |
◆ global_tf_
| geometry_msgs::TransformStamped hfl::HFL110DCU::global_tf_ |
|
private |
◆ node_handler_
| ros::NodeHandle hfl::HFL110DCU::node_handler_ |
|
private |
◆ object_header_message_
| std::shared_ptr<std_msgs::Header> hfl::HFL110DCU::object_header_message_ |
|
private |
◆ objects_
| std::vector<hflObj> hfl::HFL110DCU::objects_ |
|
private |
◆ 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 |
◆ 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 |
◆ 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 |
◆ 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 |
◆ pub_points_
| ros::Publisher hfl::HFL110DCU::pub_points_ |
|
private |
◆ row_
| uint8_t hfl::HFL110DCU::row_ |
|
private |
◆ tf_header_message_
| std::shared_ptr<std_msgs::Header> hfl::HFL110DCU::tf_header_message_ |
|
private |
◆ transform_
| cv::Mat hfl::HFL110DCU::transform_ |
|
private |
The documentation for this class was generated from the following files: