27 #ifndef _CLASS_COLISION_TIME_H_
28 #define _CLASS_COLISION_TIME_H_
38 #include <mtt/TargetListPC.h>
40 #include <sensor_msgs/PointCloud2.h>
41 #include <pcl/point_cloud.h>
42 #include <pcl/point_types.h>
43 #include <pcl/conversions.h>
44 #include <pcl_conversions/pcl_conversions.h>
45 #include <pcl_ros/transforms.h>
46 #include <tf/transform_listener.h>
47 #include <points_from_volume/points_from_volume.h>
51 #include <visualization_msgs/Marker.h>
53 #include "ros/file_log.h"
54 #include "rosgraph_msgs/Log.h"
56 #define PFLN printf("Line = %d\n", __LINE__);
81 <<
"||||||||msg_mtt||||||"<<endl
82 <<
"id: "<< i.
id<<endl
86 <<
"v_x: "<< i.
v_x<<endl
87 <<
"v_y: "<< i.
v_y<<endl
88 <<
"v_z: "<< i.
v_z<<endl;
109 <<
"||||||||msg_partial||||||"<<endl
116 <<
"horn: "<< i.
horn<<endl
118 <<
"brake: "<< i.
brake<<endl
119 <<
"clutch: "<< i.
clutch<<endl;
133 <<
"||||||||msg_velocityl||||||"<<endl
152 <<
"||||||||msg_plc||||||"<<endl
154 <<
"rpm: "<< i.
rpm<<endl;
207 <<
"||||||||msg_plc||||||"<<endl
~class_colision_time()
Class destructor.
class_colision_time()
Class constructor.
A class to detect danger situations while driving.