From 6e548f71fb5df6e9fcf76ed68434d2148f5c5e52 Mon Sep 17 00:00:00 2001 From: duongtd Date: Mon, 24 Nov 2025 13:37:43 +0700 Subject: [PATCH] change define header guard --- .../include/tf3_geometry_msgs/data_convert.h | 6 +- .../tf3_geometry_msgs/tf3_geometry_msgs.h | 56 +++++++++---------- .../include/tf3_sensor_msgs/data_convert.h | 6 +- 3 files changed, 34 insertions(+), 34 deletions(-) diff --git a/tf3_geometry_msgs/include/tf3_geometry_msgs/data_convert.h b/tf3_geometry_msgs/include/tf3_geometry_msgs/data_convert.h index c708404..bd86b16 100644 --- a/tf3_geometry_msgs/include/tf3_geometry_msgs/data_convert.h +++ b/tf3_geometry_msgs/include/tf3_geometry_msgs/data_convert.h @@ -1,5 +1,5 @@ -#ifndef DATA_CONVERT_H -#define DATA_CONVERT_H +#ifndef DATA_CONVERT_TF3_GEOMETRY_MSGS_H +#define DATA_CONVERT_TF3_GEOMETRY_MSGS_H #include #include @@ -116,4 +116,4 @@ namespace tf3 } } -#endif // DATA_CONVERT_H \ No newline at end of file +#endif // DATA_CONVERT_TF3_GEOMETRY_MSGS_H \ No newline at end of file diff --git a/tf3_geometry_msgs/include/tf3_geometry_msgs/tf3_geometry_msgs.h b/tf3_geometry_msgs/include/tf3_geometry_msgs/tf3_geometry_msgs.h index c4991c1..e896b51 100755 --- a/tf3_geometry_msgs/include/tf3_geometry_msgs/tf3_geometry_msgs.h +++ b/tf3_geometry_msgs/include/tf3_geometry_msgs/tf3_geometry_msgs.h @@ -111,7 +111,7 @@ void fromMsg(const geometry_msgs::Vector3& in, tf3::Vector3& out) */ template <> inline - const tf3::Time& getTimestamp(const geometry_msgs::Vector3Stamped& t) {return convertTime(t.header.stamp);} + const tf3::Time& getTimestamp(const geometry_msgs::Vector3Stamped& t) {return tf3::convertTime(t.header.stamp);} /** \brief Extract a frame ID from the header of a Vector message. * This function is a specialization of the getFrameId template defined in tf3/convert.h. @@ -155,7 +155,7 @@ inline geometry_msgs::Vector3Stamped toMsg(const tf3::Stamped& in) { geometry_msgs::Vector3Stamped out; - out.header.stamp = convertTime(in.stamp_); + out.header.stamp = tf3::convertTime(in.stamp_); out.header.frame_id = in.frame_id_; out.vector.x = in.getX(); out.vector.y = in.getY(); @@ -171,7 +171,7 @@ geometry_msgs::Vector3Stamped toMsg(const tf3::Stamped& in) inline void fromMsg(const geometry_msgs::Vector3Stamped& msg, tf3::Stamped& out) { - out.stamp_ = convertTime(msg.header.stamp); + out.stamp_ = tf3::convertTime(msg.header.stamp); out.frame_id_ = msg.header.frame_id; out.setData(tf3::Vector3(msg.vector.x, msg.vector.y, msg.vector.z)); } @@ -219,7 +219,7 @@ void fromMsg(const geometry_msgs::Point& in, tf3::Vector3& out) */ template <> inline - const tf3::Time& getTimestamp(const geometry_msgs::PointStamped& t) {return convertTime(t.header.stamp);} + const tf3::Time& getTimestamp(const geometry_msgs::PointStamped& t) {return tf3::convertTime(t.header.stamp);} /** \brief Extract a frame ID from the header of a Point message. * This function is a specialization of the getFrameId template defined in tf3/convert.h. @@ -261,7 +261,7 @@ void fromMsg(const geometry_msgs::PointStamped& msg, geometry_msgs::PointStamped inline geometry_msgs::PointStamped toMsg(const tf3::Stamped& in, geometry_msgs::PointStamped & out) { - out.header.stamp = convertTime(in.stamp_); + out.header.stamp = tf3::convertTime(in.stamp_); out.header.frame_id = in.frame_id_; out.point.x = in.getX(); out.point.y = in.getY(); @@ -277,7 +277,7 @@ geometry_msgs::PointStamped toMsg(const tf3::Stamped& in, geometry inline void fromMsg(const geometry_msgs::PointStamped& msg, tf3::Stamped& out) { - out.stamp_ = convertTime(msg.header.stamp); + out.stamp_ = tf3::convertTime(msg.header.stamp); out.frame_id_ = msg.header.frame_id; out.setData(tf3::Vector3(msg.point.x, msg.point.y, msg.point.z)); } @@ -328,7 +328,7 @@ void fromMsg(const geometry_msgs::Quaternion& in, tf3::Quaternion& out) */ template <> inline -const tf3::Time& getTimestamp(const geometry_msgs::QuaternionStamped& t) {return convertTime(t.header.stamp);} +const tf3::Time& getTimestamp(const geometry_msgs::QuaternionStamped& t) {return tf3::convertTime(t.header.stamp);} /** \brief Extract a frame ID from the header of a Quaternion message. * This function is a specialization of the getFrameId template defined in tf3/convert.h. @@ -371,7 +371,7 @@ inline geometry_msgs::QuaternionStamped toMsg(const tf3::Stamped& in) { geometry_msgs::QuaternionStamped out; - out.header.stamp = convertTime(in.stamp_); + out.header.stamp = tf3::convertTime(in.stamp_); out.header.frame_id = in.frame_id_; out.quaternion.w = in.getW(); out.quaternion.x = in.getX(); @@ -401,7 +401,7 @@ geometry_msgs::QuaternionStamped toMsg(const tf3::Stamped& in) inline void fromMsg(const geometry_msgs::QuaternionStamped& in, tf3::Stamped& out) { - out.stamp_ = convertTime(in.header.stamp); + out.stamp_ = tf3::convertTime(in.header.stamp); out.frame_id_ = in.header.frame_id; tf3::Quaternion tmp; fromMsg(in.quaternion, tmp); @@ -461,7 +461,7 @@ void fromMsg(const geometry_msgs::Pose& in, tf3::Transform& out) */ template <> inline - const tf3::Time& getTimestamp(const geometry_msgs::PoseStamped& t) {return convertTime(t.header.stamp);} + const tf3::Time& getTimestamp(const geometry_msgs::PoseStamped& t) {return tf3::convertTime(t.header.stamp);} /** \brief Extract a frame ID from the header of a Pose message. * This function is a specialization of the getFrameId template defined in tf3/convert.h. @@ -502,7 +502,7 @@ void fromMsg(const geometry_msgs::PoseStamped& msg, geometry_msgs::PoseStamped& inline geometry_msgs::PoseStamped toMsg(const tf3::Stamped& in, geometry_msgs::PoseStamped & out) { - out.header.stamp = convertTime(in.stamp_); + out.header.stamp = tf3::convertTime(in.stamp_); out.header.frame_id = in.frame_id_; toMsg(in.getOrigin(), out.pose.position); out.pose.orientation = toMsg(in.getRotation()); @@ -517,7 +517,7 @@ geometry_msgs::PoseStamped toMsg(const tf3::Stamped& in, geometr inline void fromMsg(const geometry_msgs::PoseStamped& msg, tf3::Stamped& out) { - out.stamp_ = convertTime(msg.header.stamp); + out.stamp_ = tf3::convertTime(msg.header.stamp); out.frame_id_ = msg.header.frame_id; tf3::Transform tmp; fromMsg(msg.pose, tmp); @@ -535,7 +535,7 @@ void fromMsg(const geometry_msgs::PoseStamped& msg, tf3::Stamped */ template <> inline - const tf3::Time& getTimestamp(const geometry_msgs::PoseWithCovarianceStamped& t) {return convertTime(t.header.stamp);} + const tf3::Time& getTimestamp(const geometry_msgs::PoseWithCovarianceStamped& t) {return tf3::convertTime(t.header.stamp);} /** \brief Extract a frame ID from the header of a PoseWithCovarianceStamped message. * This function is a specialization of the getFrameId template defined in tf3/convert.h. @@ -576,7 +576,7 @@ void fromMsg(const geometry_msgs::PoseWithCovarianceStamped& msg, geometry_msgs: inline geometry_msgs::PoseWithCovarianceStamped toMsg(const tf3::Stamped& in, geometry_msgs::PoseWithCovarianceStamped & out) { - out.header.stamp = convertTime(in.stamp_); + out.header.stamp = tf3::convertTime(in.stamp_); out.header.frame_id = in.frame_id_; toMsg(in.getOrigin(), out.pose.pose.position); out.pose.pose.orientation = toMsg(in.getRotation()); @@ -591,7 +591,7 @@ geometry_msgs::PoseWithCovarianceStamped toMsg(const tf3::Stamped& out) { - out.stamp_ = convertTime(msg.header.stamp); + out.stamp_ = tf3::convertTime(msg.header.stamp); out.frame_id_ = msg.header.frame_id; tf3::Transform tmp; fromMsg(msg.pose, tmp); @@ -659,7 +659,7 @@ void fromMsg(const tf3::TransformMsg& in, tf3::Transform& out) */ template <> inline -const tf3::Time& getTimestamp(const geometry_msgs::TransformStamped& t) {return convertTime(t.header.stamp);} +const tf3::Time& getTimestamp(const geometry_msgs::TransformStamped& t) {return tf3::convertTime(t.header.stamp);} /** \brief Extract a frame ID from the header of a Transform message. * This function is a specialization of the getFrameId template defined in tf3/convert.h. @@ -700,7 +700,7 @@ inline geometry_msgs::TransformStamped toMsg(const tf3::Stamped& in) { geometry_msgs::TransformStamped out; - out.header.stamp = convertTime(in.stamp_); + out.header.stamp = tf3::convertTime(in.stamp_); out.header.frame_id = in.frame_id_; out.transform.translation = toMsg(in.getOrigin()); out.transform.rotation = toMsg(in.getRotation()); @@ -716,7 +716,7 @@ geometry_msgs::TransformStamped toMsg(const tf3::Stamped& in) inline void fromMsg(const geometry_msgs::TransformStamped& msg, tf3::Stamped& out) { - out.stamp_ = convertTime(msg.header.stamp); + out.stamp_ = tf3::convertTime(msg.header.stamp); out.frame_id_ = msg.header.frame_id; tf3::Transform tmp; fromMsg(msg.transform, tmp); @@ -752,7 +752,7 @@ inline void doTransform(const geometry_msgs::PointStamped& t_in, geometry_msgs::PointStamped& t_out, const tf3::TransformStampedMsg& transform) { doTransform(t_in.point, t_out.point, transform); - t_out.header.stamp = convertTime(transform.header.stamp); + t_out.header.stamp = tf3::convertTime(transform.header.stamp); t_out.header.frame_id = transform.header.frame_id; } @@ -785,7 +785,7 @@ inline void doTransform(const geometry_msgs::QuaternionStamped& t_in, geometry_msgs::QuaternionStamped& t_out, const tf3::TransformStampedMsg& transform) { doTransform(t_in.quaternion, t_out.quaternion, transform); - t_out.header.stamp = convertTime(transform.header.stamp); + t_out.header.stamp = tf3::convertTime(transform.header.stamp); t_out.header.frame_id = transform.header.frame_id; } @@ -837,7 +837,7 @@ inline void doTransform(const geometry_msgs::PoseStamped& t_in, geometry_msgs::PoseStamped& t_out, const tf3::TransformStampedMsg& transform) { doTransform(t_in.pose, t_out.pose, transform); - t_out.header.stamp = convertTime(transform.header.stamp); + t_out.header.stamp = tf3::convertTime(transform.header.stamp); t_out.header.frame_id = transform.header.frame_id; } @@ -949,7 +949,7 @@ void doTransform(const geometry_msgs::PoseWithCovarianceStamped& t_in, geometry_ fromMsg(transform.transform, t); tf3::Transform v_out = t * tf3::Transform(r, v); toMsg(v_out, t_out.pose.pose); - t_out.header.stamp = convertTime(transform.header.stamp); + t_out.header.stamp = tf3::convertTime(transform.header.stamp); t_out.header.frame_id = transform.header.frame_id; t_out.pose.covariance = transformCovariance(t_in.pose.covariance, t); @@ -972,7 +972,7 @@ void doTransform(const geometry_msgs::TransformStamped& t_in, geometry_msgs::Tra tf3::Transform v_out = t * input; t_out.transform = toMsg(v_out); - t_out.header.stamp = convertTime(transform.header.stamp); + t_out.header.stamp = tf3::convertTime(transform.header.stamp); t_out.header.frame_id = transform.header.frame_id; } @@ -1004,7 +1004,7 @@ inline void doTransform(const geometry_msgs::Vector3Stamped& t_in, geometry_msgs::Vector3Stamped& t_out, const tf3::TransformStampedMsg& transform) { doTransform(t_in.vector, t_out.vector, transform); - t_out.header.stamp = convertTime(transform.header.stamp); + t_out.header.stamp = tf3::convertTime(transform.header.stamp); t_out.header.frame_id = transform.header.frame_id; } @@ -1014,7 +1014,7 @@ inline /**********************/ template <> inline -const tf3::Time& getTimestamp(const geometry_msgs::WrenchStamped& t) {return convertTime(t.header.stamp);} +const tf3::Time& getTimestamp(const geometry_msgs::WrenchStamped& t) {return tf3::convertTime(t.header.stamp);} template <> @@ -1038,7 +1038,7 @@ void fromMsg(const geometry_msgs::WrenchStamped& msg, geometry_msgs::WrenchStamp inline geometry_msgs::WrenchStamped toMsg(const tf3::Stamped>& in, geometry_msgs::WrenchStamped & out) { - out.header.stamp = convertTime(in.stamp_); + out.header.stamp = tf3::convertTime(in.stamp_); out.header.frame_id = in.frame_id_; out.wrench.force = toMsg(in[0]); out.wrench.torque = toMsg(in[1]); @@ -1049,7 +1049,7 @@ geometry_msgs::WrenchStamped toMsg(const tf3::Stamped>& out) { - out.stamp_ = convertTime(msg.header.stamp); + out.stamp_ = tf3::convertTime(msg.header.stamp); out.frame_id_ = msg.header.frame_id; tf3::Vector3 tmp; fromMsg(msg.wrench.force, tmp); @@ -1082,7 +1082,7 @@ inline void doTransform(const geometry_msgs::WrenchStamped& t_in, geometry_msgs::WrenchStamped& t_out, const tf3::TransformStampedMsg& transform) { doTransform(t_in.wrench, t_out.wrench, transform); - t_out.header.stamp = convertTime(transform.header.stamp); + t_out.header.stamp = tf3::convertTime(transform.header.stamp); t_out.header.frame_id = transform.header.frame_id; } diff --git a/tf3_sensor_msgs/include/tf3_sensor_msgs/data_convert.h b/tf3_sensor_msgs/include/tf3_sensor_msgs/data_convert.h index c708404..1d377b9 100644 --- a/tf3_sensor_msgs/include/tf3_sensor_msgs/data_convert.h +++ b/tf3_sensor_msgs/include/tf3_sensor_msgs/data_convert.h @@ -1,5 +1,5 @@ -#ifndef DATA_CONVERT_H -#define DATA_CONVERT_H +#ifndef DATA_CONVERT_TF3_SENSOR_MSGS_H +#define DATA_CONVERT_TF3_SENSOR_MSGS_H #include #include @@ -116,4 +116,4 @@ namespace tf3 } } -#endif // DATA_CONVERT_H \ No newline at end of file +#endif // DATA_CONVERT_TF3_SENSOR_MSGS_H \ No newline at end of file