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