Skip to content

Commit

Permalink
refactor(autoware_map_based_prediction): map based pred time keeper p…
Browse files Browse the repository at this point in the history
…tr (autowarefoundation#8462)

* refactor(map_based_prediction): implement time keeper by pointer

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>

* feat(map_based_prediction): set time keeper in path generator

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>

* feat: use scoped time track only when the timekeeper ptr is not null

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>

* refactor: define publish function to measure time

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>

* chore: add debug parameters for map-based prediction

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>

* chore: remove unnecessary ScopedTimeTrack instances

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>

* feat: replace member to pointer

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>

---------

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
  • Loading branch information
technolojin authored Aug 14, 2024
1 parent f7998e9 commit 991cb94
Show file tree
Hide file tree
Showing 5 changed files with 170 additions and 68 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -50,3 +50,8 @@
consider_only_routable_neighbours: false

reference_path_resolution: 0.5 #[m]

# debug parameters
publish_processing_time: false
publish_processing_time_detail: false
publish_debug_markers: false
Original file line number Diff line number Diff line change
Expand Up @@ -252,7 +252,7 @@ class MapBasedPredictionNode : public rclcpp::Node
std::unique_ptr<autoware::universe_utils::PublishedTimePublisher> published_time_publisher_;
rclcpp::Publisher<autoware::universe_utils::ProcessingTimeDetail>::SharedPtr
detailed_processing_time_publisher_;
mutable autoware::universe_utils::TimeKeeper time_keeper_;
std::shared_ptr<autoware::universe_utils::TimeKeeper> time_keeper_;

// Member Functions
void mapCallback(const LaneletMapBin::ConstSharedPtr msg);
Expand Down Expand Up @@ -343,6 +343,10 @@ class MapBasedPredictionNode : public rclcpp::Node
const TrackedObject & object, const LaneletData & current_lanelet_data,
const double object_detected_time);

void publish(
const PredictedObjects & output,
const visualization_msgs::msg::MarkerArray & debug_markers) const;

// NOTE: This function is copied from the motion_velocity_smoother package.
// TODO(someone): Consolidate functions and move them to a common
inline std::vector<double> calcTrajectoryCurvatureFrom3Points(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define MAP_BASED_PREDICTION__PATH_GENERATOR_HPP_

#include <Eigen/Eigen>
#include <autoware/universe_utils/system/time_keeper.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_perception_msgs/msg/predicted_objects.hpp>
Expand Down Expand Up @@ -82,6 +83,8 @@ class PathGenerator
public:
PathGenerator(const double sampling_time_interval, const double min_crosswalk_user_velocity);

void setTimeKeeper(std::shared_ptr<autoware::universe_utils::TimeKeeper> time_keeper_ptr);

PredictedPath generatePathForNonVehicleObject(
const TrackedObject & object, const double duration) const;

Expand Down Expand Up @@ -119,6 +122,8 @@ class PathGenerator
bool use_vehicle_acceleration_;
double acceleration_exponential_half_life_;

std::shared_ptr<autoware::universe_utils::TimeKeeper> time_keeper_;

// Member functions
PredictedPath generateStraightPath(const TrackedObject & object, const double duration) const;

Expand Down
Loading

0 comments on commit 991cb94

Please sign in to comment.