Skip to content

Commit e46c927

Browse files
authored
feat(map_based_prediction): add time_keeper (autowarefoundation#8176)
Signed-off-by: Mamoru Sobue <[email protected]>
1 parent 799f5b1 commit e46c927

File tree

2 files changed

+65
-0
lines changed

2 files changed

+65
-0
lines changed

perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
#include <autoware/universe_utils/ros/transform_listener.hpp>
2727
#include <autoware/universe_utils/ros/uuid_helper.hpp>
2828
#include <autoware/universe_utils/system/stop_watch.hpp>
29+
#include <autoware/universe_utils/system/time_keeper.hpp>
2930
#include <rclcpp/rclcpp.hpp>
3031

3132
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
@@ -222,6 +223,9 @@ class MapBasedPredictionNode : public rclcpp::Node
222223
bool remember_lost_crosswalk_users_;
223224

224225
std::unique_ptr<autoware::universe_utils::PublishedTimePublisher> published_time_publisher_;
226+
rclcpp::Publisher<autoware::universe_utils::ProcessingTimeDetail>::SharedPtr
227+
detailed_processing_time_publisher_;
228+
mutable autoware::universe_utils::TimeKeeper time_keeper_;
225229

226230
// Member Functions
227231
void mapCallback(const LaneletMapBin::ConstSharedPtr msg);

perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

+61
Original file line numberDiff line numberDiff line change
@@ -863,6 +863,11 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
863863

864864
published_time_publisher_ =
865865
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+
866871
set_param_res_ = this->add_on_set_parameters_callback(
867872
std::bind(&MapBasedPredictionNode::onParam, this, std::placeholders::_1));
868873

@@ -922,6 +927,8 @@ PredictedObject MapBasedPredictionNode::convertToPredictedObject(
922927

923928
void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg)
924929
{
930+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
931+
925932
RCLCPP_DEBUG(get_logger(), "[Map Based Prediction]: Start loading lanelet");
926933
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
927934
lanelet::utils::conversion::fromBinMsg(
@@ -938,6 +945,8 @@ void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg
938945
void MapBasedPredictionNode::trafficSignalsCallback(
939946
const TrafficLightGroupArray::ConstSharedPtr msg)
940947
{
948+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
949+
941950
traffic_signal_id_map_.clear();
942951
for (const auto & signal : msg->traffic_light_groups) {
943952
traffic_signal_id_map_[signal.traffic_light_group_id] = signal;
@@ -946,6 +955,8 @@ void MapBasedPredictionNode::trafficSignalsCallback(
946955

947956
void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPtr in_objects)
948957
{
958+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
959+
949960
stop_watch_ptr_->toc("processing_time", true);
950961

951962
// take traffic_signal
@@ -1236,6 +1247,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt
12361247
void MapBasedPredictionNode::updateCrosswalkUserHistory(
12371248
const std_msgs::msg::Header & header, const TrackedObject & object, const std::string & object_id)
12381249
{
1250+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1251+
12391252
CrosswalkUserData crosswalk_user_data;
12401253
crosswalk_user_data.header = header;
12411254
crosswalk_user_data.tracked_object = object;
@@ -1251,6 +1264,8 @@ void MapBasedPredictionNode::updateCrosswalkUserHistory(
12511264
std::string MapBasedPredictionNode::tryMatchNewObjectToDisappeared(
12521265
const std::string & object_id, std::unordered_map<std::string, TrackedObject> & current_users)
12531266
{
1267+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1268+
12541269
const auto known_match_opt = [&]() -> std::optional<std::string> {
12551270
if (!known_matches_.count(object_id)) {
12561271
return std::nullopt;
@@ -1308,6 +1323,8 @@ std::string MapBasedPredictionNode::tryMatchNewObjectToDisappeared(
13081323

13091324
bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predicted_path)
13101325
{
1326+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1327+
13111328
lanelet::BasicLineString2d predicted_path_ls;
13121329
for (const auto & p : predicted_path.path)
13131330
predicted_path_ls.emplace_back(p.position.x, p.position.y);
@@ -1325,6 +1342,8 @@ bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predict
13251342
bool MapBasedPredictionNode::doesPathCrossFence(
13261343
const PredictedPath & predicted_path, const lanelet::ConstLineString3d & fence_line)
13271344
{
1345+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1346+
13281347
// check whether the predicted path cross with fence
13291348
for (size_t i = 0; i < predicted_path.path.size() - 1; ++i) {
13301349
for (size_t j = 0; j < fence_line.size() - 1; ++j) {
@@ -1353,6 +1372,8 @@ bool MapBasedPredictionNode::isIntersecting(
13531372
PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
13541373
const TrackedObject & object)
13551374
{
1375+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1376+
13561377
auto predicted_object = convertToPredictedObject(object);
13571378
{
13581379
PredictedPath predicted_path =
@@ -1485,6 +1506,8 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
14851506

14861507
void MapBasedPredictionNode::updateObjectData(TrackedObject & object)
14871508
{
1509+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1510+
14881511
if (
14891512
object.kinematics.orientation_availability ==
14901513
autoware_perception_msgs::msg::DetectedObjectKinematics::AVAILABLE) {
@@ -1535,6 +1558,8 @@ void MapBasedPredictionNode::updateObjectData(TrackedObject & object)
15351558
void MapBasedPredictionNode::removeStaleTrafficLightInfo(
15361559
const TrackedObjects::ConstSharedPtr in_objects)
15371560
{
1561+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1562+
15381563
for (auto it = stopped_times_against_green_.begin(); it != stopped_times_against_green_.end();) {
15391564
const bool isDisappeared = std::none_of(
15401565
in_objects->objects.begin(), in_objects->objects.end(),
@@ -1551,6 +1576,8 @@ void MapBasedPredictionNode::removeStaleTrafficLightInfo(
15511576

15521577
LaneletsData MapBasedPredictionNode::getCurrentLanelets(const TrackedObject & object)
15531578
{
1579+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1580+
15541581
// obstacle point
15551582
lanelet::BasicPoint2d search_point(
15561583
object.kinematics.pose_with_covariance.pose.position.x,
@@ -1641,6 +1668,8 @@ LaneletsData MapBasedPredictionNode::getCurrentLanelets(const TrackedObject & ob
16411668
bool MapBasedPredictionNode::checkCloseLaneletCondition(
16421669
const std::pair<double, lanelet::Lanelet> & lanelet, const TrackedObject & object)
16431670
{
1671+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1672+
16441673
// Step1. If we only have one point in the centerline, we will ignore the lanelet
16451674
if (lanelet.second.centerline().size() <= 1) {
16461675
return false;
@@ -1687,6 +1716,8 @@ bool MapBasedPredictionNode::checkCloseLaneletCondition(
16871716
float MapBasedPredictionNode::calculateLocalLikelihood(
16881717
const lanelet::Lanelet & current_lanelet, const TrackedObject & object) const
16891718
{
1719+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1720+
16901721
const auto & obj_point = object.kinematics.pose_with_covariance.pose.position;
16911722

16921723
// compute yaw difference between the object and lane
@@ -1722,6 +1753,8 @@ void MapBasedPredictionNode::updateRoadUsersHistory(
17221753
const std_msgs::msg::Header & header, const TrackedObject & object,
17231754
const LaneletsData & current_lanelets_data)
17241755
{
1756+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1757+
17251758
std::string object_id = autoware::universe_utils::toHexString(object.object_id);
17261759
const auto current_lanelets = getLanelets(current_lanelets_data);
17271760

@@ -1763,6 +1796,8 @@ std::vector<PredictedRefPath> MapBasedPredictionNode::getPredictedReferencePath(
17631796
const TrackedObject & object, const LaneletsData & current_lanelets_data,
17641797
const double object_detected_time, const double time_horizon)
17651798
{
1799+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1800+
17661801
const double obj_vel = std::hypot(
17671802
object.kinematics.twist_with_covariance.twist.linear.x,
17681803
object.kinematics.twist_with_covariance.twist.linear.y);
@@ -1925,6 +1960,8 @@ Maneuver MapBasedPredictionNode::predictObjectManeuver(
19251960
const TrackedObject & object, const LaneletData & current_lanelet_data,
19261961
const double object_detected_time)
19271962
{
1963+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
1964+
19281965
// calculate maneuver
19291966
const auto current_maneuver = [&]() {
19301967
if (lane_change_detection_method_ == "time_to_change_lane") {
@@ -1975,6 +2012,8 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByTimeToLaneChange(
19752012
const TrackedObject & object, const LaneletData & current_lanelet_data,
19762013
const double /*object_detected_time*/)
19772014
{
2015+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
2016+
19782017
// Step1. Check if we have the object in the buffer
19792018
const std::string object_id = autoware::universe_utils::toHexString(object.object_id);
19802019
if (road_users_history.count(object_id) == 0) {
@@ -2046,6 +2085,8 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByLatDiffDistance(
20462085
const TrackedObject & object, const LaneletData & current_lanelet_data,
20472086
const double /*object_detected_time*/)
20482087
{
2088+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
2089+
20492090
// Step1. Check if we have the object in the buffer
20502091
const std::string object_id = autoware::universe_utils::toHexString(object.object_id);
20512092
if (road_users_history.count(object_id) == 0) {
@@ -2189,6 +2230,8 @@ geometry_msgs::msg::Pose MapBasedPredictionNode::compensateTimeDelay(
21892230
double MapBasedPredictionNode::calcRightLateralOffset(
21902231
const lanelet::ConstLineString2d & boundary_line, const geometry_msgs::msg::Pose & search_pose)
21912232
{
2233+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
2234+
21922235
std::vector<geometry_msgs::msg::Point> boundary_path(boundary_line.size());
21932236
for (size_t i = 0; i < boundary_path.size(); ++i) {
21942237
const double x = boundary_line[i].x();
@@ -2208,6 +2251,8 @@ double MapBasedPredictionNode::calcLeftLateralOffset(
22082251
void MapBasedPredictionNode::updateFuturePossibleLanelets(
22092252
const TrackedObject & object, const lanelet::routing::LaneletPaths & paths)
22102253
{
2254+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
2255+
22112256
std::string object_id = autoware::universe_utils::toHexString(object.object_id);
22122257
if (road_users_history.count(object_id) == 0) {
22132258
return;
@@ -2232,6 +2277,8 @@ void MapBasedPredictionNode::addReferencePaths(
22322277
const Maneuver & maneuver, std::vector<PredictedRefPath> & reference_paths,
22332278
const double speed_limit)
22342279
{
2280+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
2281+
22352282
if (!candidate_paths.empty()) {
22362283
updateFuturePossibleLanelets(object, candidate_paths);
22372284
const auto converted_paths = convertPathType(candidate_paths);
@@ -2251,6 +2298,8 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability(
22512298
const lanelet::routing::LaneletPaths & right_paths,
22522299
const lanelet::routing::LaneletPaths & center_paths)
22532300
{
2301+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
2302+
22542303
float left_lane_change_probability = 0.0;
22552304
float right_lane_change_probability = 0.0;
22562305
float lane_follow_probability = 0.0;
@@ -2313,6 +2362,8 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability(
23132362
std::vector<PosePath> MapBasedPredictionNode::convertPathType(
23142363
const lanelet::routing::LaneletPaths & paths)
23152364
{
2365+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
2366+
23162367
std::vector<PosePath> converted_paths;
23172368
for (const auto & path : paths) {
23182369
PosePath converted_path;
@@ -2385,6 +2436,8 @@ bool MapBasedPredictionNode::isDuplicated(
23852436
const std::pair<double, lanelet::ConstLanelet> & target_lanelet,
23862437
const LaneletsData & lanelets_data)
23872438
{
2439+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
2440+
23882441
const double CLOSE_LANELET_THRESHOLD = 0.1;
23892442
for (const auto & lanelet_data : lanelets_data) {
23902443
const auto target_lanelet_end_p = target_lanelet.second.centerline2d().back();
@@ -2402,6 +2455,8 @@ bool MapBasedPredictionNode::isDuplicated(
24022455
bool MapBasedPredictionNode::isDuplicated(
24032456
const PredictedPath & predicted_path, const std::vector<PredictedPath> & predicted_paths)
24042457
{
2458+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
2459+
24052460
const double CLOSE_PATH_THRESHOLD = 0.1;
24062461
for (const auto & prev_predicted_path : predicted_paths) {
24072462
const auto prev_path_end = prev_predicted_path.path.back().position;
@@ -2418,6 +2473,8 @@ bool MapBasedPredictionNode::isDuplicated(
24182473
std::optional<lanelet::Id> MapBasedPredictionNode::getTrafficSignalId(
24192474
const lanelet::ConstLanelet & way_lanelet)
24202475
{
2476+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
2477+
24212478
const auto traffic_light_reg_elems =
24222479
way_lanelet.regulatoryElementsAs<const lanelet::TrafficLight>();
24232480
if (traffic_light_reg_elems.empty()) {
@@ -2434,6 +2491,8 @@ std::optional<lanelet::Id> MapBasedPredictionNode::getTrafficSignalId(
24342491
std::optional<TrafficLightElement> MapBasedPredictionNode::getTrafficSignalElement(
24352492
const lanelet::Id & id)
24362493
{
2494+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
2495+
24372496
if (traffic_signal_id_map_.count(id) != 0) {
24382497
const auto & signal_elements = traffic_signal_id_map_.at(id).elements;
24392498
if (signal_elements.size() > 1) {
@@ -2450,6 +2509,8 @@ bool MapBasedPredictionNode::calcIntentionToCrossWithTrafficSignal(
24502509
const TrackedObject & object, const lanelet::ConstLanelet & crosswalk,
24512510
const lanelet::Id & signal_id)
24522511
{
2512+
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
2513+
24532514
const auto signal_color = [&] {
24542515
const auto elem_opt = getTrafficSignalElement(signal_id);
24552516
return elem_opt ? elem_opt.value().color : TrafficLightElement::UNKNOWN;

0 commit comments

Comments
 (0)