change define header guard

This commit is contained in:
duongtd 2025-11-24 13:37:43 +07:00
parent a73257c965
commit 6e548f71fb
3 changed files with 34 additions and 34 deletions

View File

@ -1,5 +1,5 @@
#ifndef DATA_CONVERT_H #ifndef DATA_CONVERT_TF3_GEOMETRY_MSGS_H
#define DATA_CONVERT_H #define DATA_CONVERT_TF3_GEOMETRY_MSGS_H
#include <tf3/time.h> #include <tf3/time.h>
#include <tf3/compat.h> #include <tf3/compat.h>
@ -116,4 +116,4 @@ namespace tf3
} }
} }
#endif // DATA_CONVERT_H #endif // DATA_CONVERT_TF3_GEOMETRY_MSGS_H

View File

@ -111,7 +111,7 @@ void fromMsg(const geometry_msgs::Vector3& in, tf3::Vector3& out)
*/ */
template <> template <>
inline 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. /** \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. * 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<tf3::Vector3>& in) geometry_msgs::Vector3Stamped toMsg(const tf3::Stamped<tf3::Vector3>& in)
{ {
geometry_msgs::Vector3Stamped out; 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.header.frame_id = in.frame_id_;
out.vector.x = in.getX(); out.vector.x = in.getX();
out.vector.y = in.getY(); out.vector.y = in.getY();
@ -171,7 +171,7 @@ geometry_msgs::Vector3Stamped toMsg(const tf3::Stamped<tf3::Vector3>& in)
inline inline
void fromMsg(const geometry_msgs::Vector3Stamped& msg, tf3::Stamped<tf3::Vector3>& out) void fromMsg(const geometry_msgs::Vector3Stamped& msg, tf3::Stamped<tf3::Vector3>& out)
{ {
out.stamp_ = convertTime(msg.header.stamp); out.stamp_ = tf3::convertTime(msg.header.stamp);
out.frame_id_ = msg.header.frame_id; out.frame_id_ = msg.header.frame_id;
out.setData(tf3::Vector3(msg.vector.x, msg.vector.y, msg.vector.z)); 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 <> template <>
inline 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. /** \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. * 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 inline
geometry_msgs::PointStamped toMsg(const tf3::Stamped<tf3::Vector3>& in, geometry_msgs::PointStamped & out) geometry_msgs::PointStamped toMsg(const tf3::Stamped<tf3::Vector3>& 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.header.frame_id = in.frame_id_;
out.point.x = in.getX(); out.point.x = in.getX();
out.point.y = in.getY(); out.point.y = in.getY();
@ -277,7 +277,7 @@ geometry_msgs::PointStamped toMsg(const tf3::Stamped<tf3::Vector3>& in, geometry
inline inline
void fromMsg(const geometry_msgs::PointStamped& msg, tf3::Stamped<tf3::Vector3>& out) void fromMsg(const geometry_msgs::PointStamped& msg, tf3::Stamped<tf3::Vector3>& out)
{ {
out.stamp_ = convertTime(msg.header.stamp); out.stamp_ = tf3::convertTime(msg.header.stamp);
out.frame_id_ = msg.header.frame_id; out.frame_id_ = msg.header.frame_id;
out.setData(tf3::Vector3(msg.point.x, msg.point.y, msg.point.z)); 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 <> template <>
inline 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. /** \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. * 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<tf3::Quaternion>& in) geometry_msgs::QuaternionStamped toMsg(const tf3::Stamped<tf3::Quaternion>& in)
{ {
geometry_msgs::QuaternionStamped out; 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.header.frame_id = in.frame_id_;
out.quaternion.w = in.getW(); out.quaternion.w = in.getW();
out.quaternion.x = in.getX(); out.quaternion.x = in.getX();
@ -401,7 +401,7 @@ geometry_msgs::QuaternionStamped toMsg(const tf3::Stamped<tf3::Quaternion>& in)
inline inline
void fromMsg(const geometry_msgs::QuaternionStamped& in, tf3::Stamped<tf3::Quaternion>& out) void fromMsg(const geometry_msgs::QuaternionStamped& in, tf3::Stamped<tf3::Quaternion>& out)
{ {
out.stamp_ = convertTime(in.header.stamp); out.stamp_ = tf3::convertTime(in.header.stamp);
out.frame_id_ = in.header.frame_id; out.frame_id_ = in.header.frame_id;
tf3::Quaternion tmp; tf3::Quaternion tmp;
fromMsg(in.quaternion, tmp); fromMsg(in.quaternion, tmp);
@ -461,7 +461,7 @@ void fromMsg(const geometry_msgs::Pose& in, tf3::Transform& out)
*/ */
template <> template <>
inline 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. /** \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. * 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 inline
geometry_msgs::PoseStamped toMsg(const tf3::Stamped<tf3::Transform>& in, geometry_msgs::PoseStamped & out) geometry_msgs::PoseStamped toMsg(const tf3::Stamped<tf3::Transform>& 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_; out.header.frame_id = in.frame_id_;
toMsg(in.getOrigin(), out.pose.position); toMsg(in.getOrigin(), out.pose.position);
out.pose.orientation = toMsg(in.getRotation()); out.pose.orientation = toMsg(in.getRotation());
@ -517,7 +517,7 @@ geometry_msgs::PoseStamped toMsg(const tf3::Stamped<tf3::Transform>& in, geometr
inline inline
void fromMsg(const geometry_msgs::PoseStamped& msg, tf3::Stamped<tf3::Transform>& out) void fromMsg(const geometry_msgs::PoseStamped& msg, tf3::Stamped<tf3::Transform>& out)
{ {
out.stamp_ = convertTime(msg.header.stamp); out.stamp_ = tf3::convertTime(msg.header.stamp);
out.frame_id_ = msg.header.frame_id; out.frame_id_ = msg.header.frame_id;
tf3::Transform tmp; tf3::Transform tmp;
fromMsg(msg.pose, tmp); fromMsg(msg.pose, tmp);
@ -535,7 +535,7 @@ void fromMsg(const geometry_msgs::PoseStamped& msg, tf3::Stamped<tf3::Transform>
*/ */
template <> template <>
inline 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. /** \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. * 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 inline
geometry_msgs::PoseWithCovarianceStamped toMsg(const tf3::Stamped<tf3::Transform>& in, geometry_msgs::PoseWithCovarianceStamped & out) geometry_msgs::PoseWithCovarianceStamped toMsg(const tf3::Stamped<tf3::Transform>& 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_; out.header.frame_id = in.frame_id_;
toMsg(in.getOrigin(), out.pose.pose.position); toMsg(in.getOrigin(), out.pose.pose.position);
out.pose.pose.orientation = toMsg(in.getRotation()); out.pose.pose.orientation = toMsg(in.getRotation());
@ -591,7 +591,7 @@ geometry_msgs::PoseWithCovarianceStamped toMsg(const tf3::Stamped<tf3::Transform
inline inline
void fromMsg(const geometry_msgs::PoseWithCovarianceStamped& msg, tf3::Stamped<tf3::Transform>& out) void fromMsg(const geometry_msgs::PoseWithCovarianceStamped& msg, tf3::Stamped<tf3::Transform>& out)
{ {
out.stamp_ = convertTime(msg.header.stamp); out.stamp_ = tf3::convertTime(msg.header.stamp);
out.frame_id_ = msg.header.frame_id; out.frame_id_ = msg.header.frame_id;
tf3::Transform tmp; tf3::Transform tmp;
fromMsg(msg.pose, tmp); fromMsg(msg.pose, tmp);
@ -659,7 +659,7 @@ void fromMsg(const tf3::TransformMsg& in, tf3::Transform& out)
*/ */
template <> template <>
inline 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. /** \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. * 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<tf3::Transform>& in) geometry_msgs::TransformStamped toMsg(const tf3::Stamped<tf3::Transform>& in)
{ {
geometry_msgs::TransformStamped out; 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.header.frame_id = in.frame_id_;
out.transform.translation = toMsg(in.getOrigin()); out.transform.translation = toMsg(in.getOrigin());
out.transform.rotation = toMsg(in.getRotation()); out.transform.rotation = toMsg(in.getRotation());
@ -716,7 +716,7 @@ geometry_msgs::TransformStamped toMsg(const tf3::Stamped<tf3::Transform>& in)
inline inline
void fromMsg(const geometry_msgs::TransformStamped& msg, tf3::Stamped<tf3::Transform>& out) void fromMsg(const geometry_msgs::TransformStamped& msg, tf3::Stamped<tf3::Transform>& out)
{ {
out.stamp_ = convertTime(msg.header.stamp); out.stamp_ = tf3::convertTime(msg.header.stamp);
out.frame_id_ = msg.header.frame_id; out.frame_id_ = msg.header.frame_id;
tf3::Transform tmp; tf3::Transform tmp;
fromMsg(msg.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) 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); 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; 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) 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); 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; 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) 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); 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; 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); fromMsg(transform.transform, t);
tf3::Transform v_out = t * tf3::Transform(r, v); tf3::Transform v_out = t * tf3::Transform(r, v);
toMsg(v_out, t_out.pose.pose); 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.header.frame_id = transform.header.frame_id;
t_out.pose.covariance = transformCovariance(t_in.pose.covariance, t); 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; tf3::Transform v_out = t * input;
t_out.transform = toMsg(v_out); 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; 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) 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); 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; t_out.header.frame_id = transform.header.frame_id;
} }
@ -1014,7 +1014,7 @@ inline
/**********************/ /**********************/
template <> template <>
inline 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 <> template <>
@ -1038,7 +1038,7 @@ void fromMsg(const geometry_msgs::WrenchStamped& msg, geometry_msgs::WrenchStamp
inline inline
geometry_msgs::WrenchStamped toMsg(const tf3::Stamped<std::array<tf3::Vector3, 2>>& in, geometry_msgs::WrenchStamped & out) geometry_msgs::WrenchStamped toMsg(const tf3::Stamped<std::array<tf3::Vector3, 2>>& 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.header.frame_id = in.frame_id_;
out.wrench.force = toMsg(in[0]); out.wrench.force = toMsg(in[0]);
out.wrench.torque = toMsg(in[1]); out.wrench.torque = toMsg(in[1]);
@ -1049,7 +1049,7 @@ geometry_msgs::WrenchStamped toMsg(const tf3::Stamped<std::array<tf3::Vector3, 2
inline inline
void fromMsg(const geometry_msgs::WrenchStamped& msg, tf3::Stamped<std::array<tf3::Vector3, 2>>& out) void fromMsg(const geometry_msgs::WrenchStamped& msg, tf3::Stamped<std::array<tf3::Vector3, 2>>& out)
{ {
out.stamp_ = convertTime(msg.header.stamp); out.stamp_ = tf3::convertTime(msg.header.stamp);
out.frame_id_ = msg.header.frame_id; out.frame_id_ = msg.header.frame_id;
tf3::Vector3 tmp; tf3::Vector3 tmp;
fromMsg(msg.wrench.force, 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) 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); 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; t_out.header.frame_id = transform.header.frame_id;
} }

View File

@ -1,5 +1,5 @@
#ifndef DATA_CONVERT_H #ifndef DATA_CONVERT_TF3_SENSOR_MSGS_H
#define DATA_CONVERT_H #define DATA_CONVERT_TF3_SENSOR_MSGS_H
#include <tf3/time.h> #include <tf3/time.h>
#include <tf3/compat.h> #include <tf3/compat.h>
@ -116,4 +116,4 @@ namespace tf3
} }
} }
#endif // DATA_CONVERT_H #endif // DATA_CONVERT_TF3_SENSOR_MSGS_H