Skip to content

Commit

Permalink
fix(path_optimizer): revert the feature of publishing processing time (
Browse files Browse the repository at this point in the history
…autowarefoundation#8160)

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 authored and chtseng committed Jul 26, 2024
1 parent 3f6cc64 commit 2d0ab2f
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include "autoware/path_optimizer/type_alias.hpp"
#include "autoware/universe_utils/ros/logger_level_configure.hpp"
#include "autoware/universe_utils/ros/polling_subscriber.hpp"
#include "autoware/universe_utils/system/stop_watch.hpp"
#include "autoware/universe_utils/system/time_keeper.hpp"
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"

Expand Down Expand Up @@ -143,6 +144,8 @@ class PathOptimizer : public rclcpp::Node
std::unique_ptr<autoware::universe_utils::LoggerLevelConfigure> logger_configure_;

std::unique_ptr<autoware::universe_utils::PublishedTimePublisher> published_time_publisher_;

autoware::universe_utils::StopWatch<std::chrono::milliseconds> stop_watch_;
};
} // namespace autoware::path_optimizer

Expand Down
8 changes: 2 additions & 6 deletions planning/autoware_path_optimizer/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,6 +223,7 @@ void PathOptimizer::resetPreviousData()
void PathOptimizer::onPath(const Path::ConstSharedPtr path_ptr)
{
time_keeper_->start_track(__func__);
stop_watch_.tic();

// check if input path is valid
if (!checkInputPath(*path_ptr, *get_clock())) {
Expand Down Expand Up @@ -270,12 +271,7 @@ void PathOptimizer::onPath(const Path::ConstSharedPtr path_ptr)

// publish calculation_time
// NOTE: This function must be called after measuring onPath calculation time
/*
const auto calculation_time_msg = createStringStamped(now(), time_keeper_ptr_->getLog());
debug_calculation_time_str_pub_->publish(calculation_time_msg);
debug_calculation_time_float_pub_->publish(
createFloat64Stamped(now(), time_keeper_ptr_->getAccumulatedTime()));
*/
debug_calculation_time_float_pub_->publish(createFloat64Stamped(now(), stop_watch_.toc()));

const auto output_traj_msg =
autoware::motion_utils::convertToTrajectory(full_traj_points, path_ptr->header);
Expand Down

0 comments on commit 2d0ab2f

Please sign in to comment.