8 #ifndef IBEO_LUX_IBEO_LUX_ROS_MSG_HANDLER_H 9 #define IBEO_LUX_IBEO_LUX_ROS_MSG_HANDLER_H 27 void fillAndPublish(
const uint8_t& type_id,
28 const std::string& frame_id,
30 IbeoTxMessage * parser_class);
32 const std::vector<Point3DL>& points,
33 pcl::PointCloud<pcl::PointXYZL> * new_msg);
34 void fillContourPoints(
35 const std::vector<Point3D>& points,
36 visualization_msgs::Marker * new_msg,
37 const std::string& frame_id);
39 const std::vector<IbeoObject>& objects,
40 visualization_msgs::MarkerArray * new_msg,
41 const std::string& frame_id);
44 ros::Time ntp_to_ros_time(
const NTPTime& time);
47 const IbeoDataHeader& class_header,
48 ibeo_msgs::IbeoDataHeader * msg_header);
50 IbeoTxMessage * parser_class,
51 ibeo_msgs::ErrorWarning * new_msg,
52 const std::string& frame_id);
54 IbeoTxMessage * parser_class,
55 ibeo_msgs::ScanData2202 * new_msg,
56 const std::string& frame_id);
58 IbeoTxMessage * parser_class,
59 ibeo_msgs::ScanData2204 * new_msg,
60 const std::string& frame_id);
62 IbeoTxMessage * parser_class,
63 ibeo_msgs::ScanData2205 * new_msg,
64 const std::string& frame_id);
66 IbeoTxMessage * parser_class,
67 ibeo_msgs::ObjectData2221 * new_msg,
68 const std::string& frame_id);
70 IbeoTxMessage * parser_class,
71 ibeo_msgs::ObjectData2225 * new_msg,
72 const std::string& frame_id);
74 IbeoTxMessage * parser_class,
75 ibeo_msgs::ObjectData2280 * new_msg,
76 const std::string& frame_id);
78 IbeoTxMessage * parser_class,
79 ibeo_msgs::CameraImage * new_msg,
80 const std::string& frame_id);
82 IbeoTxMessage * parser_class,
83 ibeo_msgs::HostVehicleState2805 * new_msg,
84 const std::string& frame_id);
86 IbeoTxMessage * parser_class,
87 ibeo_msgs::HostVehicleState2806 * new_msg,
88 const std::string& frame_id);
90 IbeoTxMessage * parser_class,
91 ibeo_msgs::HostVehicleState2807 * new_msg,
92 const std::string& frame_id);
93 visualization_msgs::Marker createWireframeMarker(
94 const float& center_x,
95 const float& center_y,
104 #endif // IBEO_LUX_IBEO_LUX_ROS_MSG_HANDLER_H