Skip to content

Commit db1bfdc

Browse files
author
M. Fatih Cırıt
committed
fix(autoware_overlay_rviz_plugin): fix subs and cleanup
Signed-off-by: M. Fatih Cırıt <mfc@leodrive.ai>
1 parent c24ad46 commit db1bfdc

File tree

1 file changed

+14
-66
lines changed

1 file changed

+14
-66
lines changed

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp

+14-66
Original file line numberDiff line numberDiff line change
@@ -120,59 +120,13 @@ void SignalDisplay::onInitialize()
120120

121121
void SignalDisplay::setupRosSubscriptions()
122122
{
123-
// Don't create a node, just use the one from the parent class
124-
auto rviz_node_ = context_->getRosNodeAbstraction().lock()->get_raw_node();
125-
126-
gear_sub_ = rviz_node_->create_subscription<autoware_auto_vehicle_msgs::msg::GearReport>(
127-
gear_topic_property_->getTopicStd(),
128-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
129-
[this](const autoware_auto_vehicle_msgs::msg::GearReport::SharedPtr msg) {
130-
updateGearData(msg);
131-
});
132-
133-
steering_sub_ = rviz_node_->create_subscription<autoware_auto_vehicle_msgs::msg::SteeringReport>(
134-
steering_topic_property_->getTopicStd(),
135-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
136-
[this](const autoware_auto_vehicle_msgs::msg::SteeringReport::SharedPtr msg) {
137-
updateSteeringData(msg);
138-
});
139-
140-
speed_sub_ = rviz_node_->create_subscription<autoware_auto_vehicle_msgs::msg::VelocityReport>(
141-
speed_topic_property_->getTopicStd(),
142-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
143-
[this](const autoware_auto_vehicle_msgs::msg::VelocityReport::SharedPtr msg) {
144-
updateSpeedData(msg);
145-
});
146-
147-
turn_signals_sub_ =
148-
rviz_node_->create_subscription<autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport>(
149-
turn_signals_topic_property_->getTopicStd(),
150-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
151-
[this](const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::SharedPtr msg) {
152-
updateTurnSignalsData(msg);
153-
});
154-
155-
hazard_lights_sub_ =
156-
rviz_node_->create_subscription<autoware_auto_vehicle_msgs::msg::HazardLightsReport>(
157-
hazard_lights_topic_property_->getTopicStd(),
158-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
159-
[this](const autoware_auto_vehicle_msgs::msg::HazardLightsReport::SharedPtr msg) {
160-
updateHazardLightsData(msg);
161-
});
162-
163-
traffic_sub_ = rviz_node_->create_subscription<autoware_perception_msgs::msg::TrafficSignal>(
164-
traffic_topic_property_->getTopicStd(),
165-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
166-
[this](const autoware_perception_msgs::msg::TrafficSignal::SharedPtr msg) {
167-
updateTrafficLightData(msg);
168-
});
169-
170-
speed_limit_sub_ = rviz_node_->create_subscription<tier4_planning_msgs::msg::VelocityLimit>(
171-
speed_limit_topic_property_->getTopicStd(),
172-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
173-
[this](const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) {
174-
updateSpeedLimitData(msg);
175-
});
123+
topic_updated_gear();
124+
topic_updated_steering();
125+
topic_updated_speed();
126+
topic_updated_speed_limit();
127+
topic_updated_turn_signals();
128+
topic_updated_hazard_lights();
129+
topic_updated_traffic();
176130
}
177131

178132
SignalDisplay::~SignalDisplay()
@@ -419,8 +373,7 @@ void SignalDisplay::topic_updated_gear()
419373
auto rviz_ros_node = context_->getRosNodeAbstraction().lock();
420374
gear_sub_ =
421375
rviz_ros_node->get_raw_node()->create_subscription<autoware_auto_vehicle_msgs::msg::GearReport>(
422-
gear_topic_property_->getTopicStd(),
423-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
376+
gear_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)),
424377
[this](const autoware_auto_vehicle_msgs::msg::GearReport::SharedPtr msg) {
425378
updateGearData(msg);
426379
});
@@ -433,8 +386,7 @@ void SignalDisplay::topic_updated_steering()
433386
auto rviz_ros_node = context_->getRosNodeAbstraction().lock();
434387
steering_sub_ = rviz_ros_node->get_raw_node()
435388
->create_subscription<autoware_auto_vehicle_msgs::msg::SteeringReport>(
436-
steering_topic_property_->getTopicStd(),
437-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
389+
steering_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)),
438390
[this](const autoware_auto_vehicle_msgs::msg::SteeringReport::SharedPtr msg) {
439391
updateSteeringData(msg);
440392
});
@@ -447,8 +399,7 @@ void SignalDisplay::topic_updated_speed()
447399
auto rviz_ros_node = context_->getRosNodeAbstraction().lock();
448400
speed_sub_ = rviz_ros_node->get_raw_node()
449401
->create_subscription<autoware_auto_vehicle_msgs::msg::VelocityReport>(
450-
speed_topic_property_->getTopicStd(),
451-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
402+
speed_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)),
452403
[this](const autoware_auto_vehicle_msgs::msg::VelocityReport::SharedPtr msg) {
453404
updateSpeedData(msg);
454405
});
@@ -462,7 +413,7 @@ void SignalDisplay::topic_updated_speed_limit()
462413
speed_limit_sub_ =
463414
rviz_ros_node->get_raw_node()->create_subscription<tier4_planning_msgs::msg::VelocityLimit>(
464415
speed_limit_topic_property_->getTopicStd(),
465-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
416+
rclcpp::QoS(rclcpp::KeepLast(10)).transient_local(),
466417
[this](const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) {
467418
updateSpeedLimitData(msg);
468419
});
@@ -477,8 +428,7 @@ void SignalDisplay::topic_updated_turn_signals()
477428
turn_signals_sub_ =
478429
rviz_ros_node->get_raw_node()
479430
->create_subscription<autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport>(
480-
turn_signals_topic_property_->getTopicStd(),
481-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
431+
turn_signals_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)),
482432
[this](const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::SharedPtr msg) {
483433
updateTurnSignalsData(msg);
484434
});
@@ -493,8 +443,7 @@ void SignalDisplay::topic_updated_hazard_lights()
493443
hazard_lights_sub_ =
494444
rviz_ros_node->get_raw_node()
495445
->create_subscription<autoware_auto_vehicle_msgs::msg::HazardLightsReport>(
496-
hazard_lights_topic_property_->getTopicStd(),
497-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
446+
hazard_lights_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)),
498447
[this](const autoware_auto_vehicle_msgs::msg::HazardLightsReport::SharedPtr msg) {
499448
updateHazardLightsData(msg);
500449
});
@@ -507,8 +456,7 @@ void SignalDisplay::topic_updated_traffic()
507456
auto rviz_ros_node = context_->getRosNodeAbstraction().lock();
508457
traffic_sub_ = rviz_ros_node->get_raw_node()
509458
->create_subscription<autoware_perception_msgs::msg::TrafficSignal>(
510-
traffic_topic_property_->getTopicStd(),
511-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
459+
traffic_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)),
512460
[this](const autoware_perception_msgs::msg::TrafficSignal::SharedPtr msg) {
513461
updateTrafficLightData(msg);
514462
});

0 commit comments

Comments
 (0)