Skip to content

Commit ad98a10

Browse files
committed
feat: add published_time publisher debug to packages
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent 36731c2 commit ad98a10

File tree

51 files changed

+292
-2
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

51 files changed

+292
-2
lines changed

control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828

2929
#include <Eigen/Core>
3030
#include <Eigen/Geometry>
31+
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
3132

3233
#include "autoware_auto_control_msgs/msg/ackermann_control_command.hpp"
3334
#include "autoware_auto_control_msgs/msg/longitudinal_command.hpp"
@@ -121,6 +122,8 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node
121122

122123
std::unique_ptr<tier4_autoware_utils::LoggerLevelConfigure> logger_configure_;
123124

125+
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
126+
124127
void publishProcessingTime(
125128
const double t_ms, const rclcpp::Publisher<Float64Stamped>::SharedPtr pub);
126129
StopWatch<std::chrono::milliseconds> stop_watch_;

control/trajectory_follower_node/src/controller_node.cpp

+8-1
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,8 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control
9191
}
9292

9393
logger_configure_ = std::make_unique<tier4_autoware_utils::LoggerLevelConfigure>(this);
94+
95+
published_time_publisher_ = tier4_autoware_utils::PublishedTimePublisher::create(this);
9496
}
9597

9698
Controller::LateralControllerMode Controller::getLateralControllerMode(
@@ -231,7 +233,12 @@ void Controller::callbackTimerControl()
231233
out.longitudinal = lon_out.control_cmd;
232234
control_cmd_pub_->publish(out);
233235

234-
// 6. publish debug marker
236+
// 6. publish published time only if enabled by parameter
237+
if (published_time_publisher_) {
238+
published_time_publisher_->publish(control_cmd_pub_, out.stamp);
239+
}
240+
241+
// 7. publish debug marker
235242
publishDebugMarker(*input_data, lat_out);
236243
}
237244

control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp

+11
Original file line numberDiff line numberDiff line change
@@ -242,6 +242,8 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options)
242242
this, get_clock(), period_ns, std::bind(&VehicleCmdGate::publishStatus, this));
243243

244244
logger_configure_ = std::make_unique<tier4_autoware_utils::LoggerLevelConfigure>(this);
245+
246+
published_time_publisher_ = tier4_autoware_utils::PublishedTimePublisher::create(this);
245247
}
246248

247249
bool VehicleCmdGate::isHeartbeatTimeout(
@@ -456,7 +458,16 @@ void VehicleCmdGate::publishControlCommands(const Commands & commands)
456458
// Publish commands
457459
vehicle_cmd_emergency_pub_->publish(vehicle_cmd_emergency);
458460
control_cmd_pub_->publish(filtered_commands.control);
461+
462+
// Publish published time only if enabled by parameter
463+
if (published_time_publisher_) {
464+
published_time_publisher_->publish(control_cmd_pub_, filtered_commands.control.stamp);
465+
}
466+
467+
// Publish pause state to api
459468
adapi_pause_->publish();
469+
470+
// Publish moderate stop state which is used for stop request
460471
moderate_stop_interface_->publish();
461472

462473
// Save ControlCmd to steering angle when disengaged

control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include <diagnostic_updater/diagnostic_updater.hpp>
2424
#include <motion_utils/vehicle/vehicle_state_checker.hpp>
2525
#include <rclcpp/rclcpp.hpp>
26+
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
2627
#include <vehicle_cmd_gate/msg/is_filter_activated.hpp>
2728
#include <vehicle_info_util/vehicle_info_util.hpp>
2829

@@ -248,6 +249,8 @@ class VehicleCmdGate : public rclcpp::Node
248249
void publishMarkers(const IsFilterActivated & filter_activated);
249250

250251
std::unique_ptr<tier4_autoware_utils::LoggerLevelConfigure> logger_configure_;
252+
253+
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
251254
};
252255

253256
} // namespace vehicle_cmd_gate

perception/detected_object_feature_remover/include/detected_object_feature_remover/detected_object_feature_remover.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
#define DETECTED_OBJECT_FEATURE_REMOVER__DETECTED_OBJECT_FEATURE_REMOVER_HPP_
1717

1818
#include <rclcpp/rclcpp.hpp>
19+
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
1920

2021
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
2122
#include <tier4_perception_msgs/msg/detected_objects_with_feature.hpp>
@@ -33,6 +34,7 @@ class DetectedObjectFeatureRemover : public rclcpp::Node
3334
private:
3435
rclcpp::Subscription<DetectedObjectsWithFeature>::SharedPtr sub_;
3536
rclcpp::Publisher<DetectedObjects>::SharedPtr pub_;
37+
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
3638
void objectCallback(const DetectedObjectsWithFeature::ConstSharedPtr input);
3739
void convert(const DetectedObjectsWithFeature & objs_with_feature, DetectedObjects & objs);
3840
};

perception/detected_object_feature_remover/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
<depend>autoware_auto_perception_msgs</depend>
1414
<depend>rclcpp</depend>
1515
<depend>rclcpp_components</depend>
16+
<depend>tier4_autoware_utils</depend>
1617
<depend>tier4_perception_msgs</depend>
1718

1819
<test_depend>ament_cmake_ros</test_depend>

perception/detected_object_feature_remover/src/detected_object_feature_remover.cpp

+8
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,9 @@ 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+
27+
// Published Time Publisher enabled only if the use_published_time is true
28+
published_time_publisher_ = tier4_autoware_utils::PublishedTimePublisher::create(this);
2629
}
2730

2831
void DetectedObjectFeatureRemover::objectCallback(
@@ -31,6 +34,11 @@ void DetectedObjectFeatureRemover::objectCallback(
3134
DetectedObjects output;
3235
convert(*input, output);
3336
pub_->publish(output);
37+
38+
// Publish published time if enabled by parameter
39+
if (published_time_publisher_) {
40+
published_time_publisher_->publish(pub_, output.header.stamp);
41+
}
3442
}
3543

3644
void DetectedObjectFeatureRemover::convert(

perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <rclcpp/rclcpp.hpp>
2121
#include <tier4_autoware_utils/geometry/geometry.hpp>
2222
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
23+
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
2324

2425
#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
2526
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
@@ -68,6 +69,8 @@ class ObjectLaneletFilterNode : public rclcpp::Node
6869
bool isPolygonOverlapLanelets(const Polygon2d &, const lanelet::ConstLanelets &);
6970
geometry_msgs::msg::Polygon setFootprint(
7071
const autoware_auto_perception_msgs::msg::DetectedObject &);
72+
73+
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
7174
};
7275

7376
} // namespace object_lanelet_filter

perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_position_filter.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
#include <rclcpp/rclcpp.hpp>
2121
#include <tier4_autoware_utils/geometry/geometry.hpp>
22+
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
2223

2324
#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
2425
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
@@ -51,6 +52,8 @@ class ObjectPositionFilterNode : public rclcpp::Node
5152
float lower_bound_y_;
5253
utils::FilterTargetLabel filter_target_;
5354
bool isObjectInBounds(const autoware_auto_perception_msgs::msg::DetectedObject & object) const;
55+
56+
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
5457
};
5558

5659
} // namespace object_position_filter

perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121

2222
#include <rclcpp/rclcpp.hpp>
2323
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
24+
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
2425

2526
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
2627
#include <sensor_msgs/msg/point_cloud2.hpp>
@@ -148,6 +149,7 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node
148149
std::shared_ptr<Debugger> debugger_;
149150
bool using_2d_validator_;
150151
std::unique_ptr<Validator> validator_;
152+
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
151153

152154
private:
153155
void onObjectsAndObstaclePointCloud(

perception/detected_object_validation/include/detected_object_validation/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <opencv2/imgproc/imgproc.hpp>
2020
#include <opencv2/opencv.hpp>
2121
#include <rclcpp/rclcpp.hpp>
22+
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
2223

2324
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
2425
#include <nav_msgs/msg/occupancy_grid.hpp>
@@ -42,6 +43,7 @@ class OccupancyGridBasedValidator : public rclcpp::Node
4243
message_filters::Subscriber<nav_msgs::msg::OccupancyGrid> occ_grid_sub_;
4344
tf2_ros::Buffer tf_buffer_;
4445
tf2_ros::TransformListener tf_listener_;
46+
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
4547

4648
typedef message_filters::sync_policies::ApproximateTime<
4749
autoware_auto_perception_msgs::msg::DetectedObjects, nav_msgs::msg::OccupancyGrid>

perception/detected_object_validation/src/object_lanelet_filter.cpp

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

5656
debug_publisher_ =
5757
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "object_lanelet_filter");
58+
59+
// Published Time Publisher enabled only if the use_published_time is true
60+
published_time_publisher_ = tier4_autoware_utils::PublishedTimePublisher::create(this);
5861
}
5962

6063
void ObjectLaneletFilterNode::mapCallback(
@@ -120,6 +123,10 @@ void ObjectLaneletFilterNode::objectCallback(
120123
}
121124
object_pub_->publish(output_object_msg);
122125

126+
if (published_time_publisher_) {
127+
published_time_publisher_->publish(object_pub_, output_object_msg.header.stamp);
128+
}
129+
123130
// Publish debug info
124131
const double pipeline_latency =
125132
std::chrono::duration<double, std::milli>(

perception/detected_object_validation/src/object_position_filter.cpp

+7
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,9 @@ 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+
46+
// Published Time Publisher enabled only if the use_published_time is true
47+
published_time_publisher_ = tier4_autoware_utils::PublishedTimePublisher::create(this);
4548
}
4649

4750
void ObjectPositionFilterNode::objectCallback(
@@ -65,6 +68,10 @@ void ObjectPositionFilterNode::objectCallback(
6568
}
6669

6770
object_pub_->publish(output_object_msg);
71+
72+
if (published_time_publisher_) {
73+
published_time_publisher_->publish(object_pub_, output_object_msg.header.stamp);
74+
}
6875
}
6976

7077
bool ObjectPositionFilterNode::isObjectInBounds(

perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp

+8
Original file line numberDiff line numberDiff line change
@@ -309,6 +309,9 @@ 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+
313+
// Published Time Publisher enabled only if the use_published_time is true
314+
published_time_publisher_ = tier4_autoware_utils::PublishedTimePublisher::create(this);
312315
}
313316
void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud(
314317
const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr & input_objects,
@@ -347,6 +350,11 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud(
347350
}
348351

349352
objects_pub_->publish(output);
353+
354+
if (published_time_publisher_) {
355+
published_time_publisher_->publish(objects_pub_, output.header.stamp);
356+
}
357+
350358
if (debugger_) {
351359
debugger_->publishRemovedObjects(removed_objects);
352360
debugger_->publishNeighborPointcloud(input_obstacle_pointcloud->header);

perception/detected_object_validation/src/occupancy_grid_based_validator.cpp

+7
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,9 @@ 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+
56+
// Published Time Publisher enabled only if the use_published_time is true
57+
published_time_publisher_ = tier4_autoware_utils::PublishedTimePublisher::create(this);
5558
}
5659

5760
void OccupancyGridBasedValidator::onObjectsAndOccGrid(
@@ -86,6 +89,10 @@ void OccupancyGridBasedValidator::onObjectsAndOccGrid(
8689

8790
objects_pub_->publish(output);
8891

92+
if (published_time_publisher_) {
93+
published_time_publisher_->publish(objects_pub_, output.header.stamp);
94+
}
95+
8996
if (enable_debug_) showDebugImage(*input_occ_grid, transformed_objects, occ_grid);
9097
}
9198

perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include <euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp>
2424
#include <rclcpp/rclcpp.hpp>
2525
#include <shape_estimation/shape_estimator.hpp>
26+
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
2627

2728
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
2829
#include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
@@ -83,6 +84,8 @@ class DetectionByTracker : public rclcpp::Node
8384

8485
detection_by_tracker::utils::TrackerIgnoreLabel tracker_ignore_;
8586

87+
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
88+
8689
void setMaxSearchRange();
8790

8891
void onObjects(

perception/detection_by_tracker/src/detection_by_tracker_core.cpp

+11
Original file line numberDiff line numberDiff line change
@@ -177,6 +177,9 @@ 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+
181+
// Published Time Publisher enabled only if the use_published_time is true
182+
published_time_publisher_ = tier4_autoware_utils::PublishedTimePublisher::create(this);
180183
}
181184

182185
void DetectionByTracker::setMaxSearchRange()
@@ -220,6 +223,10 @@ void DetectionByTracker::onObjects(
220223
!object_recognition_utils::transformObjects(
221224
objects, input_msg->header.frame_id, tf_buffer_, transformed_objects)) {
222225
objects_pub_->publish(detected_objects);
226+
227+
if (published_time_publisher_) {
228+
published_time_publisher_->publish(objects_pub_, detected_objects.header.stamp);
229+
}
223230
return;
224231
}
225232
// to simplify post processes, convert tracked_objects to DetectedObjects message.
@@ -250,6 +257,10 @@ void DetectionByTracker::onObjects(
250257
}
251258

252259
objects_pub_->publish(detected_objects);
260+
261+
if (published_time_publisher_) {
262+
published_time_publisher_->publish(objects_pub_, detected_objects.header.stamp);
263+
}
253264
}
254265

255266
void DetectionByTracker::divideUnderSegmentedObjects(

perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include <lidar_centerpoint/detection_class_remapper.hpp>
2222
#include <rclcpp/rclcpp.hpp>
2323
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
24+
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
2425
#include <tier4_autoware_utils/system/stop_watch.hpp>
2526

2627
#include <autoware_auto_perception_msgs/msg/detected_object_kinematics.hpp>
@@ -63,6 +64,8 @@ class LidarCenterPointNode : public rclcpp::Node
6364
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_{
6465
nullptr};
6566
std::unique_ptr<tier4_autoware_utils::DebugPublisher> debug_publisher_ptr_{nullptr};
67+
68+
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
6669
};
6770

6871
} // namespace centerpoint

perception/lidar_centerpoint/src/node.cpp

+7
Original file line numberDiff line numberDiff line change
@@ -126,6 +126,9 @@ 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+
130+
// Published Time Publisher enabled only if the use_published_time is true
131+
published_time_publisher_ = tier4_autoware_utils::PublishedTimePublisher::create(this);
129132
}
130133

131134
void LidarCenterPointNode::pointCloudCallback(
@@ -163,6 +166,10 @@ void LidarCenterPointNode::pointCloudCallback(
163166

164167
if (objects_sub_count > 0) {
165168
objects_pub_->publish(output_msg);
169+
170+
if (published_time_publisher_) {
171+
published_time_publisher_->publish(objects_pub_, output_msg.header.stamp);
172+
}
166173
}
167174

168175
// 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
@@ -21,6 +21,7 @@
2121
#include "tier4_autoware_utils/ros/update_param.hpp"
2222

2323
#include <rclcpp/rclcpp.hpp>
24+
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
2425
#include <tier4_autoware_utils/ros/transform_listener.hpp>
2526
#include <tier4_autoware_utils/ros/uuid_helper.hpp>
2627
#include <tier4_autoware_utils/system/stop_watch.hpp>
@@ -199,6 +200,9 @@ class MapBasedPredictionNode : public rclcpp::Node
199200
// Stop watch
200201
StopWatch<std::chrono::milliseconds> stop_watch_;
201202

203+
// PublishedTime Publisher
204+
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
205+
202206
// Member Functions
203207
void mapCallback(const HADMapBin::ConstSharedPtr msg);
204208
void trafficSignalsCallback(const TrafficSignalArray::ConstSharedPtr msg);

0 commit comments

Comments
 (0)