Go to the documentation of this file.
36 #ifndef IMAGE_PROCESSOR__HFL110DCU_H_
37 #define IMAGE_PROCESSOR__HFL110DCU_H_
42 #include <arpa/inet.h>
45 #include <geometry_msgs/TransformStamped.h>
52 #include <geometry_msgs/Point.h>
53 #include <std_msgs/UInt16MultiArray.h>
54 #include <sensor_msgs/PointCloud2.h>
56 #include <visualization_msgs/Marker.h>
57 #include <visualization_msgs/MarkerArray.h>
69 #define HFL110_MAGIC_NUMBER_16_BIT 0.000762951 // 50 / 2^16
240 HFL110DCU(std::string model, std::string version,
250 bool parseFrame(
int start_byte,
const std::vector<uint8_t>& packet)
override;
286 bool parseObjects(
int start_byte,
const std::vector<uint8_t>& packet)
override;
316 cv::Mat
initTransform(cv::Mat cameraMatrix, cv::Mat distCoeffs,
317 int width,
int height,
bool radial);
438 std::shared_ptr<std_msgs::UInt16MultiArray>
slices_;
451 #endif // IMAGE_PROCESSOR__HFL110DCU_H_
cv_bridge::CvImagePtr p_image_depth2_
Pointer to depth image second return.
unsigned uiTempSensorFeedback
Base class for the HFL110DCU cameras.
bool parseObjects(int start_byte, const std::vector< uint8_t > &packet) override
int bytes_received_
Received packet bytes from HFL110.
cv_bridge::CvImagePtr p_image_superimposed2_
Pointer to superimposed2 flags.
std::shared_ptr< std_msgs::Header > object_header_message_
Object Header message.
float_t extrinsic_vertical
std::shared_ptr< std_msgs::Header > pdm_header_message_
PDM Header message.
std::vector< hflObj > objects_
Objects vector;.
image_transport::CameraPublisher pub_ct2_
Crosstalk2 flag image publisher.
cv::Mat transform_
Transform.
unsigned TP_OBJ_MT_STATE_INACTIVE
image_transport::CameraPublisher pub_ct_
Crosstalk flag image publisher.
unsigned EM_GEN_OBJECT_DYN_PROPERTY_CROSSING_LEFT
CameraIntrinsics camera_intrinsics
unsigned TP_OBJ_MT_STATE_MEASURED
void update_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
image_transport::CameraPublisher pub_sat_
Saturated flag image publisher.
HFL110DCU v1 ethernet frame struct.
cv_bridge::CvImagePtr p_image_saturated_
Pointer to saturated flags.
unsigned EM_GEN_OBJECT_DYN_PROPERTY_STOPPED
bool parseFrame(int start_byte, const std::vector< uint8_t > &packet) override
unsigned TP_OBJ_MT_STATE_PREDICTED
HFL110DCU(std::string model, std::string version, std::string frame_id, ros::NodeHandle &node_handler)
bool processTelemetryData(const std::vector< uint8_t > &data) override
ros::NodeHandle node_handler_
ROS node handler.
std::shared_ptr< std_msgs::Header > tele_header_message_
Telemetry Header message.
geometry_msgs::TransformStamped global_tf_
ROS Transform.
std::shared_ptr< std_msgs::Header > slice_header_message_
Slice Header message.
uint8_t row_
Row and column Counter.
PointCloudReturn returns[128]
This file defines the HFL110DCU camera base class.
image_transport::CameraPublisher pub_depth_
Depth image publisher.
cv_bridge::CvImagePtr p_image_intensity_
Pointer to 16 bit intensity image.
image_transport::CameraPublisher pub_depth2_
Depth image publisher second return 2.
ros::Publisher pub_objects_
Objects publisher.
image_transport::CameraPublisher pub_si_
Superimposed flag image publisher.
cv_bridge::CvImagePtr p_image_crosstalk2_
Pointer to crosstalk2 flags.
unsigned EM_GEN_OBJECT_DYN_PROPERTY_CROSSING_RIGHT
image_transport::CameraPublisher pub_si2_
Superimposed flag image publisher.
camera_info_manager::CameraInfoManager * camera_info_manager_
HFL110DCU v1 object kinematics.
std::shared_ptr< sensor_msgs::PointCloud2 > pointcloud_
Pointcloud msg.
cv_bridge::CvImagePtr p_image_depth_
Pointer to depth image.
HFL110DCU v1 ethernet extrinsics struct.
unsigned TP_OBJ_MT_STATE_DELETED
unsigned TP_OBJ_MT_STATE_NEW
std::shared_ptr< std_msgs::UInt16MultiArray > slices_
Slices msg.
float_t extrinsic_horizontal
HFL110DCU v1 ethernet extrinsics struct.
CameraExtrinsics camera_extrinsics
HFL110DCU v1 telemetry struct.
std::shared_ptr< std_msgs::Header > frame_header_message_
Frame Header message.
float_t extrinsic_distance
unsigned EM_GEN_OBJECT_DYN_PROPERTY_ONCOMING
uint8_t expected_packet_
Return counter.
bool processObjectData(const std::vector< uint8_t > &data) override
image_transport::CameraPublisher pub_intensity2_
16 bit Intensity image publisher return 2
HFL110DCU v1 object state.
bool processSliceData(const std::vector< uint8_t > &data) override
unsigned EM_GEN_OBJECT_DYN_PROPERTY_UNKNOWN
cv_bridge::CvImagePtr p_image_intensity2_
Pointer to 16 bit intensity image second return.
bool processFrameData(const std::vector< uint8_t > &data) override
HFL110DCU v1 object dynamic property.
cv::Mat initTransform(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial)
unsigned EM_GEN_OBJECT_DYN_PROPERTY_MAX_DIFF_TYPES
std::shared_ptr< std_msgs::Header > tf_header_message_
TF Header message.
ros::Publisher pub_points_
Pointcloud publisher.
HFL110DCU v1 object geometry.
cv_bridge::CvImagePtr p_image_crosstalk_
Pointer to crosstalk flags.
unsigned EM_GEN_OBJECT_DYN_PROPERTY_STATIONARY
cv_bridge::CvImagePtr p_image_saturated2_
Pointer to saturated2 flags.
unsigned EM_GEN_OBJECT_DYN_PROPERTY_MOVING
telemetry telem_
Telemetry Data.
const float NO_RETURN_DISTANCES
uint32_t uiHardwareRevision
diagnostic_updater::Updater updater_
unsigned TP_OBJ_MT_STATE_MAX_DIFF
image_transport::CameraPublisher pub_sat2_
Saturated2 flag image publisher.
HFL110DCU v1 ethernet object struct.
Implements the HFL110DCU camera image parsing and publishing.
float focal_length_
Focal Length.
HFL110DCU v1 frame struct.
ros::Publisher pub_slices_
Slices publisher.
cv_bridge::CvImagePtr p_image_superimposed_
Pointer to superimposed flags.
image_transport::CameraPublisher pub_intensity_
16 bit Intensity image publisher
hfl_driver
Author(s): Evan Flynn
, Maxton Ginier , Gerardo Bravo , Moises Diaz
autogenerated on Wed Mar 2 2022 00:22:32