33
33
#include < string.h>
34
34
#include < time.h>
35
35
36
+ #include < ros/ros.h>
37
+ #include < std_msgs/Bool.h>
38
+ #include < std_msgs/Int32.h>
39
+ #include < sensor_msgs/PointCloud2.h>
40
+ #include < geometry_msgs/TwistStamped.h>
41
+ #include < geometry_msgs/PoseStamped.h>
42
+ #include < aslan_msgs/Lane.h>
43
+ #include < aslan_msgs/LaneArray.h>
44
+ #include < pcl_conversions/pcl_conversions.h>
45
+ #include < tf2_msgs/TFMessage.h>
46
+ #include < chrono>
47
+
36
48
class topic_data
37
49
{
38
50
public:
@@ -45,30 +57,34 @@ class topic_data
45
57
topic_data (std::string name, bool check_message);
46
58
};
47
59
60
+ class check_message_alive
61
+ {
62
+ public:
63
+ void pmap_stat_alive_callback (const std_msgs::Bool::ConstPtr& msg);
64
+ void filtered_points_alive_callback (const sensor_msgs::PointCloud2::ConstPtr& msg);
65
+ void ndt_pose_alive_callback (const geometry_msgs::PoseStamped::ConstPtr& msg);
66
+ void lane_array_alive_callback (const aslan_msgs::LaneArray::ConstPtr& msg);
67
+ void twist_cmd_alive_callback (const geometry_msgs::TwistStamped::ConstPtr& msg);
68
+ void twist_raw_alive_callback (const geometry_msgs::TwistStamped::ConstPtr& msg);
69
+ void points_raw_alive_callback (const sensor_msgs::PointCloud2::ConstPtr& msg);
70
+ void traffic_array_alive_callback (const aslan_msgs::LaneArray::ConstPtr& msg);
71
+ void closest_alive_callback (const std_msgs::Int32ConstPtr& msg, VelocitySetPath vs_path);
72
+ void final_waypoints_callback (const aslan_msgs::LaneConstPtr& msg);
73
+ void current_pose_callback (const geometry_msgs::PoseStampedConstPtr &msg);
74
+ void safety_waypoints_callback (const aslan_msgs::LaneConstPtr& msg);
75
+ void tf_callback (const tf2_msgs::TFMessageConstPtr &msg);
76
+ void radar_emergency_callback (const std_msgs::Int32::ConstPtr& msg);
77
+ diagnostic_msgs::DiagnosticStatus get_topic_diagnostics (topic_data topic);
78
+ diagnostic_msgs::DiagnosticArray generate_diagnostics ();
79
+ int RUN (int argc, char **argv);
48
80
49
- diagnostic_msgs::DiagnosticArray aslan_diagnostics_array;
50
- diagnostic_msgs::DiagnosticStatus aslan_diagnostics_status;
51
- int seq = 0 ;
52
- bool tf_msg1 = true , tf_msg2 = true , tf_msg3 = true ;
53
- bool emergency_flag = false ;
54
- bool end_of_waypoints = false ;
55
- void waypointsCallback (const aslan_msgs::LaneConstPtr& msg);
56
-
57
-
58
- topic_data pmap_stat (" pmap_stat" , false );
59
- topic_data filtered_points (" filtered_points" , false );
60
- topic_data ndt_pose (" ndt_pose" , false );
61
- topic_data lane_waypoints_array (" lane_waypoints_array" , false );
62
- topic_data twist_cmd (" twist_cmd" , true );
63
- topic_data twist_raw (" twist_raw" , false );
64
- topic_data points_raw (" points_raw" , true );
65
- topic_data traffic_waypoints_array (" traffic_waypoints_array" , false );
66
- topic_data closest_waypoint (" closest_waypoint" , false );
67
- topic_data final_waypoints (" final_waypoints" , false );
68
- topic_data current_pose (" current_pose" , false );
69
- topic_data safety_waypoints (" safety_waypoints" , false );
70
- topic_data transf (" tf" , true );
71
-
72
-
81
+ diagnostic_msgs::DiagnosticArray aslan_diagnostics_array;
82
+ diagnostic_msgs::DiagnosticStatus aslan_diagnostics_status;
83
+ int seq = 0 ;
84
+ bool tf_msg1 = true , tf_msg2 = true , tf_msg3 = true ;
85
+ bool emergency_flag = false ;
86
+ bool end_of_waypoints = false ;
87
+ // void waypointsCallback(const aslan_msgs::LaneConstPtr& msg);
73
88
74
- int FIXED_ERROR_THRESH = 200 ; // 200 ms
89
+ int FIXED_ERROR_THRESH = 200 ; // 200 ms
90
+ };
0 commit comments