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(ndt_scan_matcher): fix timestamp in service_ndt_align func #8599

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
3 changes: 2 additions & 1 deletion localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -961,7 +961,8 @@ void NDTScanMatcher::service_ndt_align_main(
diagnostics_ndt_align_->add_key_value("is_succeed_transform_initial_pose", true);

// transform pose_frame to map_frame
const auto initial_pose_msg_in_map_frame = transform(req->pose_with_covariance, transform_s2t);
auto initial_pose_msg_in_map_frame = transform(req->pose_with_covariance, transform_s2t);
initial_pose_msg_in_map_frame.header.stamp = req->pose_with_covariance.header.stamp;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

[Note]

transform :

template <class T>
T transform(const T & input, const geometry_msgs::msg::TransformStamped & transform)
{
T output;
tf2::doTransform<T>(input, output, transform);
return output;
}

tf2::doTransform

https://github.com/ros2/geometry2/blob/ae8a167e10ee65b4a44a9d7b71cd23d2579215f8/tf2_geometry_msgs/include/tf2_geometry_msgs/tf2_geometry_msgs.hpp#L789-L814

The header is copied from transform.

map_update_module_->update_map(
initial_pose_msg_in_map_frame.pose.pose.position, diagnostics_ndt_align_);

Expand Down
Loading