@@ -120,59 +120,13 @@ void SignalDisplay::onInitialize()
120
120
121
121
void SignalDisplay::setupRosSubscriptions ()
122
122
{
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 ();
176
130
}
177
131
178
132
SignalDisplay::~SignalDisplay ()
@@ -419,8 +373,7 @@ void SignalDisplay::topic_updated_gear()
419
373
auto rviz_ros_node = context_->getRosNodeAbstraction ().lock ();
420
374
gear_sub_ =
421
375
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 )),
424
377
[this ](const autoware_auto_vehicle_msgs::msg::GearReport::SharedPtr msg) {
425
378
updateGearData (msg);
426
379
});
@@ -433,8 +386,7 @@ void SignalDisplay::topic_updated_steering()
433
386
auto rviz_ros_node = context_->getRosNodeAbstraction ().lock ();
434
387
steering_sub_ = rviz_ros_node->get_raw_node ()
435
388
->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 )),
438
390
[this ](const autoware_auto_vehicle_msgs::msg::SteeringReport::SharedPtr msg) {
439
391
updateSteeringData (msg);
440
392
});
@@ -447,8 +399,7 @@ void SignalDisplay::topic_updated_speed()
447
399
auto rviz_ros_node = context_->getRosNodeAbstraction ().lock ();
448
400
speed_sub_ = rviz_ros_node->get_raw_node ()
449
401
->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 )),
452
403
[this ](const autoware_auto_vehicle_msgs::msg::VelocityReport::SharedPtr msg) {
453
404
updateSpeedData (msg);
454
405
});
@@ -462,7 +413,7 @@ void SignalDisplay::topic_updated_speed_limit()
462
413
speed_limit_sub_ =
463
414
rviz_ros_node->get_raw_node ()->create_subscription <tier4_planning_msgs::msg::VelocityLimit>(
464
415
speed_limit_topic_property_->getTopicStd (),
465
- rclcpp::QoS (rclcpp::KeepLast (10 )).durability_volatile (). reliable (),
416
+ rclcpp::QoS (rclcpp::KeepLast (10 )).transient_local (),
466
417
[this ](const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) {
467
418
updateSpeedLimitData (msg);
468
419
});
@@ -477,8 +428,7 @@ void SignalDisplay::topic_updated_turn_signals()
477
428
turn_signals_sub_ =
478
429
rviz_ros_node->get_raw_node ()
479
430
->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 )),
482
432
[this ](const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::SharedPtr msg) {
483
433
updateTurnSignalsData (msg);
484
434
});
@@ -493,8 +443,7 @@ void SignalDisplay::topic_updated_hazard_lights()
493
443
hazard_lights_sub_ =
494
444
rviz_ros_node->get_raw_node ()
495
445
->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 )),
498
447
[this ](const autoware_auto_vehicle_msgs::msg::HazardLightsReport::SharedPtr msg) {
499
448
updateHazardLightsData (msg);
500
449
});
@@ -507,8 +456,7 @@ void SignalDisplay::topic_updated_traffic()
507
456
auto rviz_ros_node = context_->getRosNodeAbstraction ().lock ();
508
457
traffic_sub_ = rviz_ros_node->get_raw_node ()
509
458
->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 )),
512
460
[this ](const autoware_perception_msgs::msg::TrafficSignal::SharedPtr msg) {
513
461
updateTrafficLightData (msg);
514
462
});
0 commit comments