This file defines the HFL110DCU image processor class. More...
#include <base_hfl110dcu.h>
#include <angles/angles.h>
#include <arpa/inet.h>
#include <camera_info_manager/camera_info_manager.h>
#include <cv_bridge/cv_bridge.h>
#include <geometry_msgs/TransformStamped.h>
#include <image_transport/image_transport.h>
#include <image_geometry/pinhole_camera_model.h>
#include <ros/package.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_ros/transform_broadcaster.h>
#include <geometry_msgs/Point.h>
#include <std_msgs/UInt16MultiArray.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/point_cloud2_iterator.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
#include <diagnostic_updater/diagnostic_updater.h>
#include <diagnostic_updater/publisher.h>
#include <string>
#include <vector>
#include <cmath>
#include <memory>
#include "ros/ros.h"
Go to the source code of this file.
Classes | |
struct | hfl::CameraExtrinsics |
HFL110DCU v1 ethernet extrinsics struct. More... | |
struct | hfl::CameraIntrinsics |
HFL110DCU v1 ethernet extrinsics struct. More... | |
class | hfl::HFL110DCU |
Implements the HFL110DCU camera image parsing and publishing. More... | |
struct | hfl::hflObj |
HFL110DCU v1 ethernet object struct. More... | |
struct | hfl::objDyn |
HFL110DCU v1 object dynamic property. More... | |
struct | hfl::objGeo |
HFL110DCU v1 object geometry. More... | |
struct | hfl::objKin |
HFL110DCU v1 object kinematics. More... | |
struct | hfl::objState |
HFL110DCU v1 object state. More... | |
struct | hfl::PointCloudReturn |
HFL110DCU v1 frame struct. More... | |
struct | hfl::telemetry |
HFL110DCU v1 telemetry struct. More... | |
struct | hfl::UdpFrame |
HFL110DCU v1 ethernet frame struct. More... | |
struct | hfl::UdpPacketHeader |
HFL110DCU v1 ethernet packet header struct. More... | |
Namespaces | |
hfl | |
Macros | |
#define | HFL110_MAGIC_NUMBER_16_BIT 0.000762951 |
Variables | |
const float | NO_RETURN_DISTANCES = NAN |
This file defines the HFL110DCU image processor class.
Definition in file hfl110dcu.h.
#define HFL110_MAGIC_NUMBER_16_BIT 0.000762951 |
Definition at line 69 of file hfl110dcu.h.
const float NO_RETURN_DISTANCES = NAN |
Definition at line 71 of file hfl110dcu.h.