Skip to content

Commit bb9fb8e

Browse files
committed
timepoint conversion: sensor_msgs
1 parent fd30f93 commit bb9fb8e

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
@@ -66,7 +66,7 @@ template<>
6666
inline
6767
tf2::TimePoint getTimestamp(const sensor_msgs::msg::PointCloud2 & p)
6868
{
69-
return tf2_ros::fromMsg(p.header.stamp);
69+
return tf2::TimePointFromMsg(p.header.stamp);
7070
}
7171

7272
// method to extract frame id from object
@@ -115,17 +115,6 @@ void doTransform(
115115
*z_out = point.z();
116116
}
117117
}
118-
inline
119-
sensor_msgs::msg::PointCloud2 toMsg(const sensor_msgs::msg::PointCloud2 & in)
120-
{
121-
return in;
122-
}
123-
inline
124-
void fromMsg(const sensor_msgs::msg::PointCloud2 & msg, sensor_msgs::msg::PointCloud2 & out)
125-
{
126-
out = msg;
127-
}
128-
129118
} // namespace tf2
130119

131120
#endif // TF2_SENSOR_MSGS__TF2_SENSOR_MSGS_HPP_

0 commit comments

Comments
 (0)