File tree Expand file tree Collapse file tree 1 file changed +1
-12
lines changed
tf2_sensor_msgs/include/tf2_sensor_msgs Expand file tree Collapse file tree 1 file changed +1
-12
lines changed Original file line number Diff line number Diff line change @@ -51,7 +51,7 @@ template<>
5151inline
5252tf2::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_
You can’t perform that action at this time.
0 commit comments