Skip to content

Commit

Permalink
fix(autoware_test_utils): set timestamp in building trajectory msg
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
  • Loading branch information
satoshi-ota committed Mar 7, 2025
1 parent 2e5c9e0 commit ff83a9e
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 0 deletions.

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

Original file line number Diff line number Diff line change
Expand Up @@ -374,6 +374,7 @@ T generateTrajectory(
using Point = typename T::_points_type::value_type;

T traj;
traj.header.stamp = rclcpp::Clock{RCL_ROS_TIME}.now();
for (size_t i = 0; i < num_points; ++i) {
const double theta = init_theta + static_cast<double>(i) * delta_theta;
const double x = static_cast<double>(i) * point_interval * std::cos(theta);
Expand All @@ -399,6 +400,7 @@ inline PathWithLaneId generateTrajectory<PathWithLaneId>(
const double init_theta, const double delta_theta, const size_t overlapping_point_index)
{
PathWithLaneId traj;
traj.header.stamp = rclcpp::Clock{RCL_ROS_TIME}.now();

for (size_t i = 0; i < num_points; i++) {
const double theta = init_theta + static_cast<double>(i) * delta_theta;
Expand Down

0 comments on commit ff83a9e

Please sign in to comment.