24
24
#include < geometry_msgs/msg/pose_stamped.hpp>
25
25
#include < sensor_msgs/msg/camera_info.hpp>
26
26
#include < sensor_msgs/msg/point_cloud2.hpp>
27
+ #include < tier4_perception_msgs/msg/traffic_light_array.hpp>
27
28
#include < tier4_perception_msgs/msg/traffic_light_roi_array.hpp>
28
- #include < tier4_perception_msgs/msg/traffic_signal_array.hpp>
29
29
30
30
#include < image_geometry/pinhole_camera_model.h>
31
31
#include < message_filters/subscriber.h>
@@ -69,7 +69,7 @@ class TrafficLightOcclusionPredictorNodelet : public rclcpp::Node
69
69
*
70
70
*/
71
71
void syncCallback (
72
- const tier4_perception_msgs::msg::TrafficSignalArray ::ConstSharedPtr in_signal_msg,
72
+ const tier4_perception_msgs::msg::TrafficLightArray ::ConstSharedPtr in_signal_msg,
73
73
const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr in_roi_msg,
74
74
const sensor_msgs::msg::CameraInfo::ConstSharedPtr in_cam_info_msg,
75
75
const sensor_msgs::msg::PointCloud2::ConstSharedPtr in_cloud_msg,
@@ -80,7 +80,7 @@ class TrafficLightOcclusionPredictorNodelet : public rclcpp::Node
80
80
* @brief publishers
81
81
*
82
82
*/
83
- rclcpp::Publisher<tier4_perception_msgs::msg::TrafficSignalArray >::SharedPtr signal_pub_;
83
+ rclcpp::Publisher<tier4_perception_msgs::msg::TrafficLightArray >::SharedPtr signal_pub_;
84
84
85
85
tf2_ros::Buffer tf_buffer_;
86
86
tf2_ros::TransformListener tf_listener_;
@@ -92,17 +92,16 @@ class TrafficLightOcclusionPredictorNodelet : public rclcpp::Node
92
92
*/
93
93
std::shared_ptr<CloudOcclusionPredictor> cloud_occlusion_predictor_;
94
94
typedef perception_utils::PrimeSynchronizer<
95
- tier4_perception_msgs::msg::TrafficSignalArray,
96
- tier4_perception_msgs::msg::TrafficLightRoiArray, sensor_msgs::msg::CameraInfo,
97
- sensor_msgs::msg::PointCloud2>
95
+ tier4_perception_msgs::msg::TrafficLightArray, tier4_perception_msgs::msg::TrafficLightRoiArray,
96
+ sensor_msgs::msg::CameraInfo, sensor_msgs::msg::PointCloud2>
98
97
SynchronizerType;
99
98
100
99
std::shared_ptr<SynchronizerType> synchronizer_;
101
100
std::shared_ptr<SynchronizerType> synchronizer_ped_;
102
101
103
102
std::vector<bool > subscribed_;
104
103
std::vector<int > occlusion_ratios_;
105
- tier4_perception_msgs::msg::TrafficSignalArray out_msg_;
104
+ tier4_perception_msgs::msg::TrafficLightArray out_msg_;
106
105
};
107
106
} // namespace traffic_light
108
107
#endif // TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__NODELET_HPP_
0 commit comments