20
20
#include < rclcpp/rclcpp.hpp>
21
21
22
22
#include < sensor_msgs/msg/image.hpp>
23
+ #include < tier4_perception_msgs/msg/traffic_light_array.hpp>
23
24
#include < tier4_perception_msgs/msg/traffic_light_roi_array.hpp>
24
- #include < tier4_perception_msgs/msg/traffic_signal_array.hpp>
25
25
26
26
#include < cv_bridge/cv_bridge.h>
27
27
#include < message_filters/subscriber.h>
@@ -51,14 +51,14 @@ class TrafficLightRoiVisualizerNodelet : public rclcpp::Node
51
51
void imageRoiCallback (
52
52
const sensor_msgs::msg::Image::ConstSharedPtr & input_image_msg,
53
53
const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_tl_roi_msg,
54
- const tier4_perception_msgs::msg::TrafficSignalArray ::ConstSharedPtr &
54
+ const tier4_perception_msgs::msg::TrafficLightArray ::ConstSharedPtr &
55
55
input_traffic_signals_msg);
56
56
57
57
void imageRoughRoiCallback (
58
58
const sensor_msgs::msg::Image::ConstSharedPtr & input_image_msg,
59
59
const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_tl_roi_msg,
60
60
const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_tl_rough_roi_msg,
61
- const tier4_perception_msgs::msg::TrafficSignalArray ::ConstSharedPtr &
61
+ const tier4_perception_msgs::msg::TrafficLightArray ::ConstSharedPtr &
62
62
input_traffic_signals_msg);
63
63
64
64
private:
@@ -90,7 +90,7 @@ class TrafficLightRoiVisualizerNodelet : public rclcpp::Node
90
90
const ClassificationResult & result);
91
91
92
92
bool getClassificationResult (
93
- int id, const tier4_perception_msgs::msg::TrafficSignalArray & traffic_signals,
93
+ int id, const tier4_perception_msgs::msg::TrafficLightArray & traffic_signals,
94
94
ClassificationResult & result);
95
95
96
96
bool getRoiFromId (
@@ -101,19 +101,18 @@ class TrafficLightRoiVisualizerNodelet : public rclcpp::Node
101
101
image_transport::SubscriberFilter image_sub_;
102
102
message_filters::Subscriber<tier4_perception_msgs::msg::TrafficLightRoiArray> roi_sub_;
103
103
message_filters::Subscriber<tier4_perception_msgs::msg::TrafficLightRoiArray> rough_roi_sub_;
104
- message_filters::Subscriber<tier4_perception_msgs::msg::TrafficSignalArray > traffic_signals_sub_;
104
+ message_filters::Subscriber<tier4_perception_msgs::msg::TrafficLightArray > traffic_signals_sub_;
105
105
image_transport::Publisher image_pub_;
106
106
typedef message_filters::sync_policies::ApproximateTime<
107
107
sensor_msgs::msg::Image, tier4_perception_msgs::msg::TrafficLightRoiArray,
108
- tier4_perception_msgs::msg::TrafficSignalArray >
108
+ tier4_perception_msgs::msg::TrafficLightArray >
109
109
SyncPolicy;
110
110
typedef message_filters::Synchronizer<SyncPolicy> Sync;
111
111
std::shared_ptr<Sync> sync_;
112
112
113
113
typedef message_filters::sync_policies::ApproximateTime<
114
114
sensor_msgs::msg::Image, tier4_perception_msgs::msg::TrafficLightRoiArray,
115
- tier4_perception_msgs::msg::TrafficLightRoiArray,
116
- tier4_perception_msgs::msg::TrafficSignalArray>
115
+ tier4_perception_msgs::msg::TrafficLightRoiArray, tier4_perception_msgs::msg::TrafficLightArray>
117
116
SyncPolicyWithRoughRoi;
118
117
typedef message_filters::Synchronizer<SyncPolicyWithRoughRoi> SyncWithRoughRoi;
119
118
std::shared_ptr<SyncWithRoughRoi> sync_with_rough_roi_;
0 commit comments