Skip to content

Commit 7af8708

Browse files
committed
timepoint conversion: sensor_msgs
1 parent ff15904 commit 7af8708

File tree

1 file changed

+1
-12
lines changed

1 file changed

+1
-12
lines changed

tf2_sensor_msgs/include/tf2_sensor_msgs/tf2_sensor_msgs.hpp

Lines changed: 1 addition & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ template<>
5151
inline
5252
tf2::TimePoint getTimestamp(const sensor_msgs::msg::PointCloud2 & p)
5353
{
54-
return tf2_ros::fromMsg(p.header.stamp);
54+
return tf2::TimePointFromMsg(p.header.stamp);
5555
}
5656

5757
// method to extract frame id from object
@@ -100,17 +100,6 @@ void doTransform(
100100
*z_out = point.z();
101101
}
102102
}
103-
inline
104-
sensor_msgs::msg::PointCloud2 toMsg(const sensor_msgs::msg::PointCloud2 & in)
105-
{
106-
return in;
107-
}
108-
inline
109-
void fromMsg(const sensor_msgs::msg::PointCloud2 & msg, sensor_msgs::msg::PointCloud2 & out)
110-
{
111-
out = msg;
112-
}
113-
114103
} // namespace tf2
115104

116105
#endif // TF2_SENSOR_MSGS__TF2_SENSOR_MSGS_HPP_

0 commit comments

Comments
 (0)