@@ -112,9 +112,10 @@ void SignalDisplay::onInitialize()
112
112
speed_limit_topic_property_->initialize (rviz_ros_node);
113
113
114
114
traffic_topic_property_ = std::make_unique<rviz_common::properties::RosTopicProperty>(
115
- " Traffic Topic" , " /perception/traffic_light_recognition/traffic_signals" ,
116
- " autoware_perception_msgs/msgs/msg/TrafficLightGroupArray" , " Topic for Traffic Light Data" ,
117
- this , SLOT (topic_updated_traffic ()));
115
+ " Traffic Topic" ,
116
+ " /planning/scenario_planning/lane_driving/behavior_planning/debug/traffic_signal" ,
117
+ " autoware_perception_msgs/msgs/msg/TrafficLightGroup" , " Topic for Traffic Light Data" , this ,
118
+ SLOT (topic_updated_traffic ()));
118
119
traffic_topic_property_->initialize (rviz_ros_node);
119
120
}
120
121
@@ -192,7 +193,7 @@ void SignalDisplay::onDisable()
192
193
}
193
194
194
195
void SignalDisplay::updateTrafficLightData (
195
- const autoware_perception_msgs::msg::TrafficLightGroupArray ::ConstSharedPtr msg)
196
+ const autoware_perception_msgs::msg::TrafficLightGroup ::ConstSharedPtr msg)
196
197
{
197
198
std::lock_guard<std::mutex> lock (property_mutex_);
198
199
@@ -458,14 +459,13 @@ void SignalDisplay::topic_updated_traffic()
458
459
// resubscribe to the topic
459
460
traffic_sub_.reset ();
460
461
auto rviz_ros_node = context_->getRosNodeAbstraction ().lock ();
461
- traffic_sub_ =
462
- rviz_ros_node->get_raw_node ()
463
- ->create_subscription <autoware_perception_msgs::msg::TrafficLightGroupArray>(
464
- traffic_topic_property_->getTopicStd (),
465
- rclcpp::QoS (rclcpp::KeepLast (10 )).durability_volatile ().reliable (),
466
- [this ](const autoware_perception_msgs::msg::TrafficLightGroupArray::SharedPtr msg) {
467
- updateTrafficLightData (msg);
468
- });
462
+ traffic_sub_ = rviz_ros_node->get_raw_node ()
463
+ ->create_subscription <autoware_perception_msgs::msg::TrafficLightGroup>(
464
+ traffic_topic_property_->getTopicStd (),
465
+ rclcpp::QoS (rclcpp::KeepLast (10 )).durability_volatile ().reliable (),
466
+ [this ](const autoware_perception_msgs::msg::TrafficLightGroup::SharedPtr msg) {
467
+ updateTrafficLightData (msg);
468
+ });
469
469
}
470
470
471
471
} // namespace autoware_overlay_rviz_plugin
0 commit comments