Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(autoware_mpc_lateral_controller): add timestamp and frame ID to published trajectory (#8164) #1452

Merged
merged 1 commit into from
Aug 8, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion control/autoware_mpc_lateral_controller/src/mpc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -804,8 +804,10 @@ Trajectory MPC::calculatePredictedTrajectory(
const auto frenet = m_vehicle_model_ptr->calculatePredictedTrajectoryInFrenetCoordinate(
mpc_matrix.Aex, mpc_matrix.Bex, mpc_matrix.Cex, mpc_matrix.Wex, x0, Uex, reference_trajectory,
dt);
const auto frenet_clipped = MPCUtils::convertToAutowareTrajectory(
auto frenet_clipped = MPCUtils::convertToAutowareTrajectory(
MPCUtils::clipTrajectoryByLength(frenet, predicted_length));
frenet_clipped.header.stamp = m_clock->now();
frenet_clipped.header.frame_id = "map";
m_debug_frenet_predicted_trajectory_pub->publish(frenet_clipped);
}

Expand Down
Loading