Skip to content

Commit 752bb0b

Browse files
committed
feat: change publish() function name and improve readability
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent 187f73d commit 752bb0b

File tree

30 files changed

+44
-138
lines changed

30 files changed

+44
-138
lines changed

common/tier4_autoware_utils/include/tier4_autoware_utils/ros/published_time_publisher.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,8 @@ class PublishedTimePublisher
3737
{
3838
}
3939

40-
void publish(const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp)
40+
void publish_if_subscribed(
41+
const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp)
4142
{
4243
const auto & gid_key = publisher->get_gid();
4344

@@ -57,7 +58,7 @@ class PublishedTimePublisher
5758
}
5859
}
5960

60-
void publish(
61+
void publish_if_subscribed(
6162
const rclcpp::PublisherBase::ConstSharedPtr & publisher, const std_msgs::msg::Header & header)
6263
{
6364
const auto & gid_key = publisher->get_gid();

control/trajectory_follower_node/src/controller_node.cpp

+2-4
Original file line numberDiff line numberDiff line change
@@ -233,10 +233,8 @@ void Controller::callbackTimerControl()
233233
out.longitudinal = lon_out.control_cmd;
234234
control_cmd_pub_->publish(out);
235235

236-
// 6. publish published time only if there are subscribers more than 1
237-
published_time_publisher_->publish(control_cmd_pub_, out.stamp);
238-
239-
// 7. publish debug marker
236+
// 6. publish debug
237+
published_time_publisher_->publish_if_subscribed(control_cmd_pub_, out.stamp);
240238
publishDebugMarker(*input_data, lat_out);
241239
}
242240

control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp

+2-7
Original file line numberDiff line numberDiff line change
@@ -458,14 +458,9 @@ void VehicleCmdGate::publishControlCommands(const Commands & commands)
458458
// Publish commands
459459
vehicle_cmd_emergency_pub_->publish(vehicle_cmd_emergency);
460460
control_cmd_pub_->publish(filtered_commands.control);
461-
462-
// Publish published time only if there are subscribers more than 1
463-
published_time_publisher_->publish(control_cmd_pub_, filtered_commands.control.stamp);
464-
465-
// Publish pause state to api
461+
published_time_publisher_->publish_if_subscribed(
462+
control_cmd_pub_, filtered_commands.control.stamp);
466463
adapi_pause_->publish();
467-
468-
// Publish moderate stop state which is used for stop request
469464
moderate_stop_interface_->publish();
470465

471466
// Save ControlCmd to steering angle when disengaged

perception/detected_object_feature_remover/README.md

+2
Original file line numberDiff line numberDiff line change
@@ -22,4 +22,6 @@ The `detected_object_feature_remover` is a package to convert topic-type from `D
2222

2323
## Parameters
2424

25+
None
26+
2527
## Assumptions / Known limits

perception/detected_object_feature_remover/src/detected_object_feature_remover.cpp

+1-4
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,6 @@ DetectedObjectFeatureRemover::DetectedObjectFeatureRemover(const rclcpp::NodeOpt
2323
pub_ = this->create_publisher<DetectedObjects>("~/output", rclcpp::QoS(1));
2424
sub_ = this->create_subscription<DetectedObjectsWithFeature>(
2525
"~/input", 1, std::bind(&DetectedObjectFeatureRemover::objectCallback, this, _1));
26-
2726
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
2827
}
2928

@@ -33,9 +32,7 @@ void DetectedObjectFeatureRemover::objectCallback(
3332
DetectedObjects output;
3433
convert(*input, output);
3534
pub_->publish(output);
36-
37-
// Publish published time only if there are subscribers more than 1
38-
published_time_publisher_->publish(pub_, output.header.stamp);
35+
published_time_publisher_->publish_if_subscribed(pub_, output.header.stamp);
3936
}
4037

4138
void DetectedObjectFeatureRemover::convert(

perception/detected_object_validation/src/object_lanelet_filter.cpp

+1-4
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,6 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod
5555

5656
debug_publisher_ =
5757
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "object_lanelet_filter");
58-
5958
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
6059
}
6160

@@ -121,9 +120,7 @@ void ObjectLaneletFilterNode::objectCallback(
121120
++index;
122121
}
123122
object_pub_->publish(output_object_msg);
124-
125-
// Publish published time only if there are subscribers more than 1
126-
published_time_publisher_->publish(object_pub_, output_object_msg.header.stamp);
123+
published_time_publisher_->publish_if_subscribed(object_pub_, output_object_msg.header.stamp);
127124

128125
// Publish debug info
129126
const double pipeline_latency =

perception/detected_object_validation/src/object_position_filter.cpp

+1-4
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,6 @@ ObjectPositionFilterNode::ObjectPositionFilterNode(const rclcpp::NodeOptions & n
4242
"input/object", rclcpp::QoS{1}, std::bind(&ObjectPositionFilterNode::objectCallback, this, _1));
4343
object_pub_ = this->create_publisher<autoware_auto_perception_msgs::msg::DetectedObjects>(
4444
"output/object", rclcpp::QoS{1});
45-
4645
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
4746
}
4847

@@ -67,9 +66,7 @@ void ObjectPositionFilterNode::objectCallback(
6766
}
6867

6968
object_pub_->publish(output_object_msg);
70-
71-
// Publish published time only if there are subscribers more than 1
72-
published_time_publisher_->publish(object_pub_, output_object_msg.header.stamp);
69+
published_time_publisher_->publish_if_subscribed(object_pub_, output_object_msg.header.stamp);
7370
}
7471

7572
bool ObjectPositionFilterNode::isObjectInBounds(

perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp

+1-5
Original file line numberDiff line numberDiff line change
@@ -309,7 +309,6 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator(
309309

310310
const bool enable_debugger = declare_parameter<bool>("enable_debugger", false);
311311
if (enable_debugger) debugger_ = std::make_shared<Debugger>(this);
312-
313312
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
314313
}
315314
void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud(
@@ -349,10 +348,7 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud(
349348
}
350349

351350
objects_pub_->publish(output);
352-
353-
// Publish published time only if there are subscribers more than 1
354-
published_time_publisher_->publish(objects_pub_, output.header.stamp);
355-
351+
published_time_publisher_->publish_if_subscribed(objects_pub_, output.header.stamp);
356352
if (debugger_) {
357353
debugger_->publishRemovedObjects(removed_objects);
358354
debugger_->publishNeighborPointcloud(input_obstacle_pointcloud->header);

perception/detected_object_validation/src/occupancy_grid_based_validator.cpp

+1-4
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,6 @@ OccupancyGridBasedValidator::OccupancyGridBasedValidator(const rclcpp::NodeOptio
5252

5353
mean_threshold_ = declare_parameter<float>("mean_threshold", 0.6);
5454
enable_debug_ = declare_parameter<bool>("enable_debug", false);
55-
5655
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
5756
}
5857

@@ -87,9 +86,7 @@ void OccupancyGridBasedValidator::onObjectsAndOccGrid(
8786
}
8887

8988
objects_pub_->publish(output);
90-
91-
// Publish published time only if there are subscribers more than 1
92-
published_time_publisher_->publish(objects_pub_, output.header.stamp);
89+
published_time_publisher_->publish_if_subscribed(objects_pub_, output.header.stamp);
9390

9491
if (enable_debug_) showDebugImage(*input_occ_grid, transformed_objects, occ_grid);
9592
}

perception/detection_by_tracker/src/detection_by_tracker_core.cpp

+2-8
Original file line numberDiff line numberDiff line change
@@ -177,7 +177,6 @@ DetectionByTracker::DetectionByTracker(const rclcpp::NodeOptions & node_options)
177177
cluster_ = std::make_shared<euclidean_cluster::VoxelGridBasedEuclideanCluster>(
178178
false, 10, 10000, 0.7, 0.3, 0);
179179
debugger_ = std::make_shared<Debugger>(this);
180-
181180
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
182181
}
183182

@@ -223,10 +222,7 @@ void DetectionByTracker::onObjects(
223222
!object_recognition_utils::transformObjects(
224223
objects, input_msg->header.frame_id, tf_buffer_, transformed_objects)) {
225224
objects_pub_->publish(detected_objects);
226-
227-
// Publish published time only if there are subscribers more than 1
228-
published_time_publisher_->publish(objects_pub_, detected_objects.header.stamp);
229-
225+
published_time_publisher_->publish_if_subscribed(objects_pub_, detected_objects.header.stamp);
230226
return;
231227
}
232228
// to simplify post processes, convert tracked_objects to DetectedObjects message.
@@ -257,10 +253,8 @@ void DetectionByTracker::onObjects(
257253
}
258254

259255
objects_pub_->publish(detected_objects);
256+
published_time_publisher_->publish_if_subscribed(objects_pub_, detected_objects.header.stamp);
260257
debugger_->publishProcessingTime();
261-
262-
// Publish published time only if there are subscribers more than 1
263-
published_time_publisher_->publish(objects_pub_, detected_objects.header.stamp);
264258
}
265259

266260
void DetectionByTracker::divideUnderSegmentedObjects(

perception/lidar_centerpoint/src/node.cpp

+1-4
Original file line numberDiff line numberDiff line change
@@ -126,7 +126,6 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti
126126
RCLCPP_INFO(this->get_logger(), "TensorRT engine is built and shutdown node.");
127127
rclcpp::shutdown();
128128
}
129-
130129
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
131130
}
132131

@@ -165,9 +164,7 @@ void LidarCenterPointNode::pointCloudCallback(
165164

166165
if (objects_sub_count > 0) {
167166
objects_pub_->publish(output_msg);
168-
169-
// Publish published time only if there are subscribers more than 1
170-
published_time_publisher_->publish(objects_pub_, output_msg.header.stamp);
167+
published_time_publisher_->publish_if_subscribed(objects_pub_, output_msg.header.stamp);
171168
}
172169

173170
// add processing time for debug

perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp

-4
Original file line numberDiff line numberDiff line change
@@ -200,10 +200,6 @@ class MapBasedPredictionNode : public rclcpp::Node
200200
std::vector<double> distance_set_for_no_intention_to_walk_;
201201
std::vector<double> timeout_set_for_no_intention_to_walk_;
202202

203-
// Stop watch
204-
StopWatch<std::chrono::milliseconds> stop_watch_;
205-
206-
// PublishedTime Publisher
207203
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
208204

209205
// Member Functions

perception/map_based_prediction/src/map_based_prediction_node.cpp

+1-5
Original file line numberDiff line numberDiff line change
@@ -812,7 +812,6 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
812812
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "map_based_prediction");
813813

814814
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
815-
816815
set_param_res_ = this->add_on_set_parameters_callback(
817816
std::bind(&MapBasedPredictionNode::onParam, this, std::placeholders::_1));
818817

@@ -1114,10 +1113,7 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt
11141113

11151114
// Publish Results
11161115
pub_objects_->publish(output);
1117-
1118-
// Publish published time only if there are subscribers more than 1
1119-
published_time_publisher_->publish(pub_objects_, output.header.stamp);
1120-
1116+
published_time_publisher_->publish_if_subscribed(pub_objects_, output.header.stamp);
11211117
pub_debug_markers_->publish(debug_markers);
11221118
const auto processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
11231119
const auto cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);

perception/multi_object_tracker/src/multi_object_tracker_core.cpp

+1-4
Original file line numberDiff line numberDiff line change
@@ -236,7 +236,6 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
236236
data_association_ = std::make_unique<DataAssociation>(
237237
can_assign_matrix, max_dist_matrix, max_area_matrix, min_area_matrix, max_rad_matrix,
238238
min_iou_matrix);
239-
240239
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
241240
}
242241

@@ -470,9 +469,7 @@ void MultiObjectTracker::publish(const rclcpp::Time & time) const
470469

471470
// Publish
472471
tracked_objects_pub_->publish(output_msg);
473-
474-
// Publish published time only if there are subscribers more than 1
475-
published_time_publisher_->publish(tracked_objects_pub_, output_msg.header.stamp);
472+
published_time_publisher_->publish_if_subscribed(tracked_objects_pub_, output_msg.header.stamp);
476473

477474
// Debugger Publish if enabled
478475
debugger_->publishProcessingTime();

perception/object_merger/src/object_association_merger/node.cpp

+1-4
Original file line numberDiff line numberDiff line change
@@ -125,7 +125,6 @@ ObjectAssociationMergerNode::ObjectAssociationMergerNode(const rclcpp::NodeOptio
125125
stop_watch_ptr_ = std::make_unique<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>>();
126126
stop_watch_ptr_->tic("cyclic_time");
127127
stop_watch_ptr_->tic("processing_time");
128-
129128
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
130129
}
131130

@@ -225,14 +224,12 @@ void ObjectAssociationMergerNode::objectsCallback(
225224

226225
// publish output msg
227226
merged_object_pub_->publish(output_msg);
227+
published_time_publisher_->publish_if_subscribed(merged_object_pub_, output_msg.header.stamp);
228228
// publish processing time
229229
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
230230
"debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true));
231231
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
232232
"debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true));
233-
234-
// Publish published time only if there are subscribers more than 1
235-
published_time_publisher_->publish(merged_object_pub_, output_msg.header.stamp);
236233
}
237234
} // namespace object_association
238235

perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp

+2-4
Original file line numberDiff line numberDiff line change
@@ -234,7 +234,6 @@ OccupancyGridMapOutlierFilterComponent::OccupancyGridMapOutlierFilterComponent(
234234
if (enable_debugger) {
235235
debugger_ptr_ = std::make_shared<Debugger>(*this);
236236
}
237-
238237
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
239238
}
240239

@@ -330,9 +329,8 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2(
330329
return;
331330
}
332331
pointcloud_pub_->publish(std::move(base_link_frame_filtered_pc_ptr));
333-
334-
// Publish published time only if there are subscribers more than 1
335-
published_time_publisher_->publish(pointcloud_pub_, ogm_frame_filtered_pc.header.stamp);
332+
published_time_publisher_->publish_if_subscribed(
333+
pointcloud_pub_, ogm_frame_filtered_pc.header.stamp);
336334
}
337335
if (debugger_ptr_) {
338336
debugger_ptr_->publishHighConfidence(high_confidence_pc, ogm_frame_pc.header);

perception/shape_estimation/src/node.cpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,6 @@ ShapeEstimationNode::ShapeEstimationNode(const rclcpp::NodeOptions & node_option
5858
stop_watch_ptr_ = std::make_unique<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>>();
5959
stop_watch_ptr_->tic("cyclic_time");
6060
stop_watch_ptr_->tic("processing_time");
61-
6261
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
6362
}
6463

@@ -122,8 +121,7 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared
122121

123122
// Publish
124123
pub_->publish(output_msg);
125-
// Publish published time only if there are subscribers more than 1
126-
published_time_publisher_->publish(pub_, output_msg.header.stamp);
124+
published_time_publisher_->publish_if_subscribed(pub_, output_msg.header.stamp);
127125
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
128126
"debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true));
129127
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(

perception/tracking_object_merger/src/decorative_tracker_merger.cpp

+2-5
Original file line numberDiff line numberDiff line change
@@ -158,7 +158,6 @@ DecorativeTrackerMergerNode::DecorativeTrackerMergerNode(const rclcpp::NodeOptio
158158
stop_watch_ptr_ = std::make_unique<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>>();
159159
stop_watch_ptr_->tic("cyclic_time");
160160
stop_watch_ptr_->tic("processing_time");
161-
162161
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
163162
}
164163

@@ -224,10 +223,8 @@ void DecorativeTrackerMergerNode::mainObjectsCallback(
224223
this->decorativeMerger(main_sensor_type_, main_objects);
225224
const auto & tracked_objects = getTrackedObjects(main_objects->header);
226225
merged_object_pub_->publish(tracked_objects);
227-
228-
merged_object_pub_->publish(getTrackedObjects(main_objects->header));
229-
// Publish published time only if there are subscribers more than 1
230-
published_time_publisher_->publish(merged_object_pub_, tracked_objects.header.stamp);
226+
published_time_publisher_->publish_if_subscribed(
227+
merged_object_pub_, tracked_objects.header.stamp);
231228
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
232229
"debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true));
233230
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(

planning/behavior_path_planner/src/behavior_path_planner_node.cpp

+1-5
Original file line numberDiff line numberDiff line change
@@ -172,7 +172,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
172172
}
173173

174174
logger_configure_ = std::make_unique<tier4_autoware_utils::LoggerLevelConfigure>(this);
175-
176175
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
177176
}
178177

@@ -415,10 +414,7 @@ void BehaviorPathPlannerNode::run()
415414

416415
if (!path->points.empty()) {
417416
path_publisher_->publish(*path);
418-
419-
// Publish published time only if there are subscribers more than 1
420-
published_time_publisher_->publish(path_publisher_, path->header.stamp);
421-
417+
published_time_publisher_->publish_if_subscribed(path_publisher_, path->header.stamp);
422418
} else {
423419
RCLCPP_ERROR_THROTTLE(
424420
get_logger(), *get_clock(), 5000, "behavior path output is empty! Stop publish.");

planning/behavior_velocity_planner/src/node.cpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -159,7 +159,6 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
159159
}
160160

161161
logger_configure_ = std::make_unique<tier4_autoware_utils::LoggerLevelConfigure>(this);
162-
163162
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
164163
}
165164

@@ -401,8 +400,7 @@ void BehaviorVelocityPlannerNode::onTrigger(
401400
lk.unlock();
402401

403402
path_pub_->publish(output_path_msg);
404-
// Publish published time only if there are subscribers more than 1
405-
published_time_publisher_->publish(path_pub_, output_path_msg.header.stamp);
403+
published_time_publisher_->publish_if_subscribed(path_pub_, output_path_msg.header.stamp);
406404
stop_reason_diag_pub_->publish(planner_manager_.getStopReasonDiag());
407405

408406
if (debug_viz_pub_->get_subscription_count() > 0) {

planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -104,7 +104,6 @@ MotionVelocitySmootherNode::MotionVelocitySmootherNode(const rclcpp::NodeOptions
104104
clock_ = get_clock();
105105

106106
logger_configure_ = std::make_unique<tier4_autoware_utils::LoggerLevelConfigure>(this);
107-
108107
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
109108
}
110109

@@ -316,8 +315,8 @@ void MotionVelocitySmootherNode::publishTrajectory(const TrajectoryPoints & traj
316315
Trajectory publishing_trajectory = motion_utils::convertToTrajectory(trajectory);
317316
publishing_trajectory.header = base_traj_raw_ptr_->header;
318317
pub_trajectory_->publish(publishing_trajectory);
319-
// Publish published time only if there are subscribers more than 1
320-
published_time_publisher_->publish(pub_trajectory_, publishing_trajectory.header.stamp);
318+
published_time_publisher_->publish_if_subscribed(
319+
pub_trajectory_, publishing_trajectory.header.stamp);
321320
}
322321

323322
void MotionVelocitySmootherNode::onCurrentOdometry(const Odometry::ConstSharedPtr msg)

0 commit comments

Comments
 (0)