Skip to content

Commit

Permalink
Update getTimestamp and getFramId to not return const references (ros…
Browse files Browse the repository at this point in the history
…-perception#14)

* Remove return of std::move from fromMsg for Time.

Windows VC++ was complaining that we were returning a pointer
to a temporary.  To avoid this, don't return a pointer, and
just construct and return an object, which C++11 should be
able to elide the copy for (see
http://stackoverflow.com/questions/14856344/when-should-stdmove-be-used-on-a-function-return-value

Signed-off-by: Chris Lalancette <[email protected]>

* Fix silly typos.

Signed-off-by: Chris Lalancette <[email protected]>

* Make getTimestamp not return const ref

* Update getTimestamp template specialisations

* Make getFrameId not return const ref
  • Loading branch information
dhood authored Apr 25, 2017
1 parent 110fd71 commit 3ac358a
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 16 deletions.
8 changes: 4 additions & 4 deletions tf2/include/tf2/convert.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,27 +59,27 @@ template <class T>
* \return The timestamp associated with the data.
*/
template <class T>
const tf2::TimePoint& getTimestamp(const T& t);
tf2::TimePoint getTimestamp(const T& t);

/**\brief Get the frame_id from data
* \param t The data input.
* \return The frame_id associated with the data.
*/
template <class T>
const std::string& getFrameId(const T& t);
std::string getFrameId(const T& t);



/* An implementation for Stamped<P> datatypes */
template <class P>
const tf2::TimePoint& getTimestamp(const tf2::Stamped<P>& t)
tf2::TimePoint getTimestamp(const tf2::Stamped<P>& t)
{
return t.stamp_;
}

/* An implementation for Stamped<P> datatypes */
template <class P>
const std::string& getFrameId(const tf2::Stamped<P>& t)
std::string getFrameId(const tf2::Stamped<P>& t)
{
return t.frame_id_;
}
Expand Down
20 changes: 10 additions & 10 deletions tf2_geometry_msgs/include/tf2_geometry_msgs/tf2_geometry_msgs.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ KDL::Frame gmTransformToKDL(const geometry_msgs::msg::TransformStamped& t)
*/
template <>
inline
const tf2::TimePoint& getTimestamp(const geometry_msgs::msg::Vector3Stamped& t) {return tf2_ros::fromMsg(t.header.stamp);}
tf2::TimePoint getTimestamp(const geometry_msgs::msg::Vector3Stamped& t) {return tf2_ros::fromMsg(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 tf2/convert.h.
Expand All @@ -79,7 +79,7 @@ inline
*/
template <>
inline
const std::string& getFrameId(const geometry_msgs::msg::Vector3Stamped& t) {return t.header.frame_id;}
std::string getFrameId(const geometry_msgs::msg::Vector3Stamped& t) {return t.header.frame_id;}

/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs Vector type.
* This function is a specialization of the doTransform template defined in tf2/convert.h.
Expand Down Expand Up @@ -134,7 +134,7 @@ void fromMsg(const geometry_msgs::msg::Vector3Stamped& msg, geometry_msgs::msg::
*/
template <>
inline
const tf2::TimePoint& getTimestamp(const geometry_msgs::msg::PointStamped& t) {return tf2_ros::fromMsg(t.header.stamp);}
tf2::TimePoint getTimestamp(const geometry_msgs::msg::PointStamped& t) {return tf2_ros::fromMsg(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 tf2/convert.h.
Expand All @@ -143,7 +143,7 @@ inline
*/
template <>
inline
const std::string& getFrameId(const geometry_msgs::msg::PointStamped& t) {return t.header.frame_id;}
std::string getFrameId(const geometry_msgs::msg::PointStamped& t) {return t.header.frame_id;}

/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs Point type.
* This function is a specialization of the doTransform template defined in tf2/convert.h.
Expand Down Expand Up @@ -197,7 +197,7 @@ void fromMsg(const geometry_msgs::msg::PointStamped& msg, geometry_msgs::msg::Po
*/
template <>
inline
const tf2::TimePoint& getTimestamp(const geometry_msgs::msg::PoseStamped& t) {return tf2_ros::fromMsg(t.header.stamp);}
tf2::TimePoint getTimestamp(const geometry_msgs::msg::PoseStamped& t) {return tf2_ros::fromMsg(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 tf2/convert.h.
Expand All @@ -206,7 +206,7 @@ inline
*/
template <>
inline
const std::string& getFrameId(const geometry_msgs::msg::PoseStamped& t) {return t.header.frame_id;}
std::string getFrameId(const geometry_msgs::msg::PoseStamped& t) {return t.header.frame_id;}

/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs Pose type.
* This function is a specialization of the doTransform template defined in tf2/convert.h.
Expand Down Expand Up @@ -297,7 +297,7 @@ void fromMsg(const geometry_msgs::msg::Quaternion& in, tf2::Quaternion& out)
*/
template <>
inline
const tf2::TimePoint& getTimestamp(const geometry_msgs::msg::QuaternionStamped& t) {return tf2_ros::fromMsg(t.header.stamp);}
tf2::TimePoint getTimestamp(const geometry_msgs::msg::QuaternionStamped& t) {return tf2_ros::fromMsg(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 tf2/convert.h.
Expand All @@ -306,7 +306,7 @@ const tf2::TimePoint& getTimestamp(const geometry_msgs::msg::QuaternionStamped&
*/
template <>
inline
const std::string& getFrameId(const geometry_msgs::msg::QuaternionStamped& t) {return t.header.frame_id;}
std::string getFrameId(const geometry_msgs::msg::QuaternionStamped& t) {return t.header.frame_id;}

/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs Quaternion type.
* This function is a specialization of the doTransform template defined in tf2/convert.h.
Expand Down Expand Up @@ -395,7 +395,7 @@ void fromMsg(const geometry_msgs::msg::QuaternionStamped& in, tf2::Stamped<tf2::
*/
template <>
inline
const tf2::TimePoint& getTimestamp(const geometry_msgs::msg::TransformStamped& t) {return tf2_ros::fromMsg(t.header.stamp);}
tf2::TimePoint getTimestamp(const geometry_msgs::msg::TransformStamped& t) {return tf2_ros::fromMsg(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 tf2/convert.h.
Expand All @@ -404,7 +404,7 @@ const tf2::TimePoint& getTimestamp(const geometry_msgs::msg::TransformStamped& t
*/
template <>
inline
const std::string& getFrameId(const geometry_msgs::msg::TransformStamped& t) {return t.header.frame_id;}
std::string getFrameId(const geometry_msgs::msg::TransformStamped& t) {return t.header.frame_id;}

/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs Transform type.
* This function is a specialization of the doTransform template defined in tf2/convert.h.
Expand Down
4 changes: 2 additions & 2 deletions tf2_sensor_msgs/include/tf2_sensor_msgs/tf2_sensor_msgs.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,12 +46,12 @@ namespace tf2
// method to extract timestamp from object
template <>
inline
const builtin_interfaces::msg::Time& getTimestamp(const sensor_msgs::PointCloud2& p) {return p.header.stamp;}
tf2::TimePoint getTimestamp(const sensor_msgs::PointCloud2& p) {return p.header.stamp;}

// method to extract frame id from object
template <>
inline
const std::string& getFrameId(const sensor_msgs::PointCloud2 &p) {return p.header.frame_id;}
std::string getFrameId(const sensor_msgs::PointCloud2 &p) {return p.header.frame_id;}

// this method needs to be implemented by client library developers
template <>
Expand Down

0 comments on commit 3ac358a

Please sign in to comment.