@@ -863,6 +863,11 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
863
863
864
864
published_time_publisher_ =
865
865
std::make_unique<autoware::universe_utils::PublishedTimePublisher>(this );
866
+ detailed_processing_time_publisher_ =
867
+ this ->create_publisher <autoware::universe_utils::ProcessingTimeDetail>(
868
+ " ~/debug/processing_time_detail_ms" , 1 );
869
+ time_keeper_ = autoware::universe_utils::TimeKeeper (detailed_processing_time_publisher_);
870
+
866
871
set_param_res_ = this ->add_on_set_parameters_callback (
867
872
std::bind (&MapBasedPredictionNode::onParam, this , std::placeholders::_1));
868
873
@@ -922,6 +927,8 @@ PredictedObject MapBasedPredictionNode::convertToPredictedObject(
922
927
923
928
void MapBasedPredictionNode::mapCallback (const LaneletMapBin::ConstSharedPtr msg)
924
929
{
930
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
931
+
925
932
RCLCPP_DEBUG (get_logger (), " [Map Based Prediction]: Start loading lanelet" );
926
933
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
927
934
lanelet::utils::conversion::fromBinMsg (
@@ -938,6 +945,8 @@ void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg
938
945
void MapBasedPredictionNode::trafficSignalsCallback (
939
946
const TrafficLightGroupArray::ConstSharedPtr msg)
940
947
{
948
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
949
+
941
950
traffic_signal_id_map_.clear ();
942
951
for (const auto & signal : msg->traffic_light_groups ) {
943
952
traffic_signal_id_map_[signal .traffic_light_group_id ] = signal ;
@@ -946,6 +955,8 @@ void MapBasedPredictionNode::trafficSignalsCallback(
946
955
947
956
void MapBasedPredictionNode::objectsCallback (const TrackedObjects::ConstSharedPtr in_objects)
948
957
{
958
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
959
+
949
960
stop_watch_ptr_->toc (" processing_time" , true );
950
961
951
962
// take traffic_signal
@@ -1236,6 +1247,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt
1236
1247
void MapBasedPredictionNode::updateCrosswalkUserHistory (
1237
1248
const std_msgs::msg::Header & header, const TrackedObject & object, const std::string & object_id)
1238
1249
{
1250
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1251
+
1239
1252
CrosswalkUserData crosswalk_user_data;
1240
1253
crosswalk_user_data.header = header;
1241
1254
crosswalk_user_data.tracked_object = object;
@@ -1251,6 +1264,8 @@ void MapBasedPredictionNode::updateCrosswalkUserHistory(
1251
1264
std::string MapBasedPredictionNode::tryMatchNewObjectToDisappeared (
1252
1265
const std::string & object_id, std::unordered_map<std::string, TrackedObject> & current_users)
1253
1266
{
1267
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1268
+
1254
1269
const auto known_match_opt = [&]() -> std::optional<std::string> {
1255
1270
if (!known_matches_.count (object_id)) {
1256
1271
return std::nullopt;
@@ -1308,6 +1323,8 @@ std::string MapBasedPredictionNode::tryMatchNewObjectToDisappeared(
1308
1323
1309
1324
bool MapBasedPredictionNode::doesPathCrossAnyFence (const PredictedPath & predicted_path)
1310
1325
{
1326
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1327
+
1311
1328
lanelet::BasicLineString2d predicted_path_ls;
1312
1329
for (const auto & p : predicted_path.path )
1313
1330
predicted_path_ls.emplace_back (p.position .x , p.position .y );
@@ -1325,6 +1342,8 @@ bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predict
1325
1342
bool MapBasedPredictionNode::doesPathCrossFence (
1326
1343
const PredictedPath & predicted_path, const lanelet::ConstLineString3d & fence_line)
1327
1344
{
1345
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1346
+
1328
1347
// check whether the predicted path cross with fence
1329
1348
for (size_t i = 0 ; i < predicted_path.path .size () - 1 ; ++i) {
1330
1349
for (size_t j = 0 ; j < fence_line.size () - 1 ; ++j) {
@@ -1353,6 +1372,8 @@ bool MapBasedPredictionNode::isIntersecting(
1353
1372
PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser (
1354
1373
const TrackedObject & object)
1355
1374
{
1375
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1376
+
1356
1377
auto predicted_object = convertToPredictedObject (object);
1357
1378
{
1358
1379
PredictedPath predicted_path =
@@ -1485,6 +1506,8 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
1485
1506
1486
1507
void MapBasedPredictionNode::updateObjectData (TrackedObject & object)
1487
1508
{
1509
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1510
+
1488
1511
if (
1489
1512
object.kinematics .orientation_availability ==
1490
1513
autoware_perception_msgs::msg::DetectedObjectKinematics::AVAILABLE) {
@@ -1535,6 +1558,8 @@ void MapBasedPredictionNode::updateObjectData(TrackedObject & object)
1535
1558
void MapBasedPredictionNode::removeStaleTrafficLightInfo (
1536
1559
const TrackedObjects::ConstSharedPtr in_objects)
1537
1560
{
1561
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1562
+
1538
1563
for (auto it = stopped_times_against_green_.begin (); it != stopped_times_against_green_.end ();) {
1539
1564
const bool isDisappeared = std::none_of (
1540
1565
in_objects->objects .begin (), in_objects->objects .end (),
@@ -1551,6 +1576,8 @@ void MapBasedPredictionNode::removeStaleTrafficLightInfo(
1551
1576
1552
1577
LaneletsData MapBasedPredictionNode::getCurrentLanelets (const TrackedObject & object)
1553
1578
{
1579
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1580
+
1554
1581
// obstacle point
1555
1582
lanelet::BasicPoint2d search_point (
1556
1583
object.kinematics .pose_with_covariance .pose .position .x ,
@@ -1641,6 +1668,8 @@ LaneletsData MapBasedPredictionNode::getCurrentLanelets(const TrackedObject & ob
1641
1668
bool MapBasedPredictionNode::checkCloseLaneletCondition (
1642
1669
const std::pair<double , lanelet::Lanelet> & lanelet, const TrackedObject & object)
1643
1670
{
1671
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1672
+
1644
1673
// Step1. If we only have one point in the centerline, we will ignore the lanelet
1645
1674
if (lanelet.second .centerline ().size () <= 1 ) {
1646
1675
return false ;
@@ -1687,6 +1716,8 @@ bool MapBasedPredictionNode::checkCloseLaneletCondition(
1687
1716
float MapBasedPredictionNode::calculateLocalLikelihood (
1688
1717
const lanelet::Lanelet & current_lanelet, const TrackedObject & object) const
1689
1718
{
1719
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1720
+
1690
1721
const auto & obj_point = object.kinematics .pose_with_covariance .pose .position ;
1691
1722
1692
1723
// compute yaw difference between the object and lane
@@ -1722,6 +1753,8 @@ void MapBasedPredictionNode::updateRoadUsersHistory(
1722
1753
const std_msgs::msg::Header & header, const TrackedObject & object,
1723
1754
const LaneletsData & current_lanelets_data)
1724
1755
{
1756
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1757
+
1725
1758
std::string object_id = autoware::universe_utils::toHexString (object.object_id );
1726
1759
const auto current_lanelets = getLanelets (current_lanelets_data);
1727
1760
@@ -1763,6 +1796,8 @@ std::vector<PredictedRefPath> MapBasedPredictionNode::getPredictedReferencePath(
1763
1796
const TrackedObject & object, const LaneletsData & current_lanelets_data,
1764
1797
const double object_detected_time, const double time_horizon)
1765
1798
{
1799
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1800
+
1766
1801
const double obj_vel = std::hypot (
1767
1802
object.kinematics .twist_with_covariance .twist .linear .x ,
1768
1803
object.kinematics .twist_with_covariance .twist .linear .y );
@@ -1925,6 +1960,8 @@ Maneuver MapBasedPredictionNode::predictObjectManeuver(
1925
1960
const TrackedObject & object, const LaneletData & current_lanelet_data,
1926
1961
const double object_detected_time)
1927
1962
{
1963
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
1964
+
1928
1965
// calculate maneuver
1929
1966
const auto current_maneuver = [&]() {
1930
1967
if (lane_change_detection_method_ == " time_to_change_lane" ) {
@@ -1975,6 +2012,8 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByTimeToLaneChange(
1975
2012
const TrackedObject & object, const LaneletData & current_lanelet_data,
1976
2013
const double /* object_detected_time*/ )
1977
2014
{
2015
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
2016
+
1978
2017
// Step1. Check if we have the object in the buffer
1979
2018
const std::string object_id = autoware::universe_utils::toHexString (object.object_id );
1980
2019
if (road_users_history.count (object_id) == 0 ) {
@@ -2046,6 +2085,8 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByLatDiffDistance(
2046
2085
const TrackedObject & object, const LaneletData & current_lanelet_data,
2047
2086
const double /* object_detected_time*/ )
2048
2087
{
2088
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
2089
+
2049
2090
// Step1. Check if we have the object in the buffer
2050
2091
const std::string object_id = autoware::universe_utils::toHexString (object.object_id );
2051
2092
if (road_users_history.count (object_id) == 0 ) {
@@ -2189,6 +2230,8 @@ geometry_msgs::msg::Pose MapBasedPredictionNode::compensateTimeDelay(
2189
2230
double MapBasedPredictionNode::calcRightLateralOffset (
2190
2231
const lanelet::ConstLineString2d & boundary_line, const geometry_msgs::msg::Pose & search_pose)
2191
2232
{
2233
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
2234
+
2192
2235
std::vector<geometry_msgs::msg::Point > boundary_path (boundary_line.size ());
2193
2236
for (size_t i = 0 ; i < boundary_path.size (); ++i) {
2194
2237
const double x = boundary_line[i].x ();
@@ -2208,6 +2251,8 @@ double MapBasedPredictionNode::calcLeftLateralOffset(
2208
2251
void MapBasedPredictionNode::updateFuturePossibleLanelets (
2209
2252
const TrackedObject & object, const lanelet::routing::LaneletPaths & paths)
2210
2253
{
2254
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
2255
+
2211
2256
std::string object_id = autoware::universe_utils::toHexString (object.object_id );
2212
2257
if (road_users_history.count (object_id) == 0 ) {
2213
2258
return ;
@@ -2232,6 +2277,8 @@ void MapBasedPredictionNode::addReferencePaths(
2232
2277
const Maneuver & maneuver, std::vector<PredictedRefPath> & reference_paths,
2233
2278
const double speed_limit)
2234
2279
{
2280
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
2281
+
2235
2282
if (!candidate_paths.empty ()) {
2236
2283
updateFuturePossibleLanelets (object, candidate_paths);
2237
2284
const auto converted_paths = convertPathType (candidate_paths);
@@ -2251,6 +2298,8 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability(
2251
2298
const lanelet::routing::LaneletPaths & right_paths,
2252
2299
const lanelet::routing::LaneletPaths & center_paths)
2253
2300
{
2301
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
2302
+
2254
2303
float left_lane_change_probability = 0.0 ;
2255
2304
float right_lane_change_probability = 0.0 ;
2256
2305
float lane_follow_probability = 0.0 ;
@@ -2313,6 +2362,8 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability(
2313
2362
std::vector<PosePath> MapBasedPredictionNode::convertPathType (
2314
2363
const lanelet::routing::LaneletPaths & paths)
2315
2364
{
2365
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
2366
+
2316
2367
std::vector<PosePath> converted_paths;
2317
2368
for (const auto & path : paths) {
2318
2369
PosePath converted_path;
@@ -2385,6 +2436,8 @@ bool MapBasedPredictionNode::isDuplicated(
2385
2436
const std::pair<double , lanelet::ConstLanelet> & target_lanelet,
2386
2437
const LaneletsData & lanelets_data)
2387
2438
{
2439
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
2440
+
2388
2441
const double CLOSE_LANELET_THRESHOLD = 0.1 ;
2389
2442
for (const auto & lanelet_data : lanelets_data) {
2390
2443
const auto target_lanelet_end_p = target_lanelet.second .centerline2d ().back ();
@@ -2402,6 +2455,8 @@ bool MapBasedPredictionNode::isDuplicated(
2402
2455
bool MapBasedPredictionNode::isDuplicated (
2403
2456
const PredictedPath & predicted_path, const std::vector<PredictedPath> & predicted_paths)
2404
2457
{
2458
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
2459
+
2405
2460
const double CLOSE_PATH_THRESHOLD = 0.1 ;
2406
2461
for (const auto & prev_predicted_path : predicted_paths) {
2407
2462
const auto prev_path_end = prev_predicted_path.path .back ().position ;
@@ -2418,6 +2473,8 @@ bool MapBasedPredictionNode::isDuplicated(
2418
2473
std::optional<lanelet::Id> MapBasedPredictionNode::getTrafficSignalId (
2419
2474
const lanelet::ConstLanelet & way_lanelet)
2420
2475
{
2476
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
2477
+
2421
2478
const auto traffic_light_reg_elems =
2422
2479
way_lanelet.regulatoryElementsAs <const lanelet::TrafficLight>();
2423
2480
if (traffic_light_reg_elems.empty ()) {
@@ -2434,6 +2491,8 @@ std::optional<lanelet::Id> MapBasedPredictionNode::getTrafficSignalId(
2434
2491
std::optional<TrafficLightElement> MapBasedPredictionNode::getTrafficSignalElement (
2435
2492
const lanelet::Id & id)
2436
2493
{
2494
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
2495
+
2437
2496
if (traffic_signal_id_map_.count (id) != 0 ) {
2438
2497
const auto & signal_elements = traffic_signal_id_map_.at (id).elements ;
2439
2498
if (signal_elements.size () > 1 ) {
@@ -2450,6 +2509,8 @@ bool MapBasedPredictionNode::calcIntentionToCrossWithTrafficSignal(
2450
2509
const TrackedObject & object, const lanelet::ConstLanelet & crosswalk,
2451
2510
const lanelet::Id & signal_id)
2452
2511
{
2512
+ autoware::universe_utils::ScopedTimeTrack st (__func__, time_keeper_);
2513
+
2453
2514
const auto signal_color = [&] {
2454
2515
const auto elem_opt = getTrafficSignalElement (signal_id);
2455
2516
return elem_opt ? elem_opt.value ().color : TrafficLightElement::UNKNOWN;
0 commit comments