generated from vortexntnu/vortex-template-repo
-
Notifications
You must be signed in to change notification settings - Fork 0
ros pose-tf transform functions #27
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
Merged
Merged
Changes from 1 commit
Commits
Show all changes
4 commits
Select commit
Hold shift + click to select a range
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,137 @@ | ||
| #ifndef VORTEX_UTILS__ROS_TRANSFORMS_HPP_ | ||
| #define VORTEX_UTILS__ROS_TRANSFORMS_HPP_ | ||
|
|
||
| #include <geometry_msgs/msg/pose_array.hpp> | ||
| #include <geometry_msgs/msg/pose_stamped.hpp> | ||
| #include <geometry_msgs/msg/pose_with_covariance_stamped.hpp> | ||
|
|
||
| #include <tf2/exceptions.h> | ||
| #include <tf2/time.h> | ||
| #include <tf2_ros/buffer.h> | ||
|
|
||
| namespace vortex::utils::ros_transforms { | ||
|
|
||
| /** | ||
| * @brief Transform a stamped pose into a target frame using TF. | ||
| * | ||
| * Applies a TF transform to a geometry_msgs::msg::PoseStamped message, | ||
| * producing a pose expressed in the specified target frame. | ||
| * | ||
| * The input pose timestamp is used for TF lookup. If no valid transform | ||
| * is available within the specified timeout, the transformation fails. | ||
| * | ||
| * @param tf_buffer TF buffer used for transform lookup | ||
| * @param in Input PoseStamped message | ||
| * @param target_frame Target frame ID | ||
| * @param out Output PoseStamped message in the target frame | ||
| * @param logger ROS logger used for warning output | ||
| * @param timeout Maximum duration to wait for a valid transform | ||
| * @return true if the transform succeeded, false otherwise | ||
| */ | ||
| inline bool transform_pose(tf2_ros::Buffer& tf_buffer, | ||
| const geometry_msgs::msg::PoseStamped& in, | ||
| const std::string& target_frame, | ||
| geometry_msgs::msg::PoseStamped& out, | ||
| rclcpp::Logger logger, | ||
| tf2::Duration timeout = tf2::durationFromSec(0.00)) { | ||
| try { | ||
| tf_buffer.transform(in, out, target_frame, timeout); | ||
| return true; | ||
| } catch (const tf2::TransformException& ex) { | ||
| RCLCPP_WARN(logger, "TF transform failed from '%s' to '%s': %s", | ||
| in.header.frame_id.c_str(), target_frame.c_str(), | ||
| ex.what()); | ||
| return false; | ||
| } | ||
| } | ||
|
|
||
| /** | ||
| * @brief Transform a stamped pose with covariance into a target frame using TF. | ||
| * | ||
| * Applies a TF transform to a geometry_msgs::msg::PoseWithCovarianceStamped | ||
| * message. Both the pose and its 6×6 covariance matrix are transformed | ||
| * according to the rigid-body frame transform. | ||
| * | ||
| * The covariance is rotated into the target frame but is not otherwise | ||
| * modified (no uncertainty inflation or filtering is applied). | ||
| * | ||
| * @param tf_buffer TF buffer used for transform lookup | ||
| * @param in Input PoseWithCovarianceStamped message | ||
| * @param target_frame Target frame ID | ||
| * @param out Output PoseWithCovarianceStamped message in the target frame | ||
| * @param logger ROS logger used for warning output | ||
| * @param timeout Maximum duration to wait for a valid transform | ||
| * @return true if the transform succeeded, false otherwise | ||
| */ | ||
| inline bool transform_pose( | ||
| tf2_ros::Buffer& tf_buffer, | ||
| const geometry_msgs::msg::PoseWithCovarianceStamped& in, | ||
| const std::string& target_frame, | ||
| geometry_msgs::msg::PoseWithCovarianceStamped& out, | ||
| rclcpp::Logger logger, | ||
| tf2::Duration timeout = tf2::durationFromSec(0.00)) { | ||
| try { | ||
| tf_buffer.transform(in, out, target_frame, timeout); | ||
| return true; | ||
| } catch (const tf2::TransformException& ex) { | ||
| RCLCPP_WARN(logger, "TF transform failed from '%s' to '%s': %s", | ||
| in.header.frame_id.c_str(), target_frame.c_str(), | ||
| ex.what()); | ||
| return false; | ||
| } | ||
| } | ||
|
|
||
| /** | ||
| * @brief Transform all poses in a PoseArray into a target frame using TF. | ||
| * | ||
| * Each pose in the input PoseArray is individually transformed using the | ||
| * array header (frame ID and timestamp). The output PoseArray contains | ||
| * only successfully transformed poses and is expressed in the target frame. | ||
| * | ||
| * TF does not natively support PoseArray, so each pose is internally | ||
| * wrapped as a PoseStamped for transformation. | ||
| * | ||
| * @param tf_buffer TF buffer used for transform lookup | ||
| * @param in Input PoseArray message | ||
| * @param target_frame Target frame ID | ||
| * @param out Output PoseArray message in the target frame | ||
| * @param logger ROS logger used for warning output | ||
| * @param timeout Maximum duration to wait for each pose transform | ||
| * @return true if all poses were successfully transformed, false otherwise | ||
| */ | ||
| inline bool transform_pose(tf2_ros::Buffer& tf_buffer, | ||
| const geometry_msgs::msg::PoseArray& in, | ||
| const std::string& target_frame, | ||
| geometry_msgs::msg::PoseArray& out, | ||
| rclcpp::Logger logger, | ||
| tf2::Duration timeout = tf2::durationFromSec(0.0)) { | ||
| out.poses.clear(); | ||
| out.poses.reserve(in.poses.size()); | ||
|
|
||
| out.header.stamp = in.header.stamp; | ||
| out.header.frame_id = target_frame; | ||
|
|
||
| geometry_msgs::msg::PoseStamped in_ps, out_ps; | ||
| in_ps.header = in.header; | ||
|
|
||
| for (const auto& pose : in.poses) { | ||
| in_ps.pose = pose; | ||
|
|
||
| try { | ||
| tf_buffer.transform(in_ps, out_ps, target_frame, timeout); | ||
| out.poses.push_back(out_ps.pose); | ||
| } catch (const tf2::TransformException& ex) { | ||
| RCLCPP_WARN(logger, | ||
| "TF transform failed for PoseArray element " | ||
| "from '%s' to '%s': %s", | ||
| in.header.frame_id.c_str(), target_frame.c_str(), | ||
| ex.what()); | ||
| return false; | ||
| } | ||
| } | ||
| return true; | ||
| } | ||
|
|
||
| } // namespace vortex::utils::ros_transforms | ||
|
|
||
| #endif // VORTEX_UTILS__ROS_TRANSFORMS_HPP_ | ||
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Personally not a big fan of catching exceptions and logging inside library functions. I would let the user (thats probably you anyway 😆 ) handle those, so the catching and logging (and logger) is customizable. But then we are at a point where these functions are just wrappers around the templated tf2 function. So that begs the question, what is the point/gain of these, other than not having to manually write the try-catch block?
I feel like we could meet in the middle here and keep the bool return (and try-catch), but let the user handle the logging.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
tf2 does not support transformation of PoseArray. Therefore I just felt like creating overloads to have a unified interface for pose transformations.
I agree with you regarding the catching and logging