Using ROS 2? Check out the ROS 2 tf2 tutorials.
Note: This tutorial assumes you have completed the intermediate tutorials.. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Transforming your own datatypes
Description: This tutorial explains which methods you need to implement to make tf2 transform your own datatypes.Tutorial Level: ADVANCED
Contents
Requirements for a Library Port
cpp
Implement the following functions for each datatype:
1 namespace tf2
2 {
3 /**\brief The templated function expected to be able to do a transform
4 *
5 * This is the method which tf2 will use to try to apply a transform for any given datatype.
6 * \param data_in The data to be transformed.
7 * \param data_out A reference to the output data. Note this can point to data in and the method should be mutation safe.
8 * \param transform The transform to apply to data_in to fill data_out.
9 *
10 * This method needs to be implemented by client library developers
11 */
12 template <class T>
13 void doTransform(const T& data_in, T& data_out, const geometry_msgs::TransformStamped& transform);
14
15 /**\brief Get the timestamp from data
16 * \param t The data input.
17 * \return The timestamp associated with the data.
18 */
19 template <class T>
20 const ros::Time& getTimestamp(const T& t);
21
22 /**\brief Get the frame_id from data
23 * \param t The data input.
24 * \return The frame_id associated with the data.
25 */
26 template <class T>
27 const std::string& getFrameId(const T& t);
28 }
py
Python implementation for PointStamped
1 def do_transform_point(point, transform):
2 p = transform_to_kdl(transform) * PyKDL.Vector(point.point.x, point.point.y, point.point.z)
3 res = PointStamped()
4 res.point.x = p[0]
5 res.point.y = p[1]
6 res.point.z = p[2]
7 res.header = transform.header
8 return res
9 tf2_py.TransformRegistration().add(PointStamped, do_transform_point)