Skip to content

Commit aa56ec1

Browse files
committed
timepoint conversion: tf2_ros
1 parent bb9fb8e commit aa56ec1

File tree

1 file changed

+4
-22
lines changed

1 file changed

+4
-22
lines changed

tf2_ros/include/tf2_ros/buffer_interface.h

Lines changed: 4 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -52,40 +52,22 @@ namespace tf2_ros
5252

5353
inline builtin_interfaces::msg::Time toMsg(const tf2::TimePoint & t)
5454
{
55-
std::chrono::nanoseconds ns =
56-
std::chrono::duration_cast<std::chrono::nanoseconds>(t.time_since_epoch());
57-
std::chrono::seconds s =
58-
std::chrono::duration_cast<std::chrono::seconds>(t.time_since_epoch());
59-
builtin_interfaces::msg::Time time_msg;
60-
time_msg.sec = static_cast<int32_t>(s.count());
61-
time_msg.nanosec = static_cast<uint32_t>(ns.count() % 1000000000ull);
62-
return time_msg;
55+
return tf2::toMsg<tf2::TimePoint, builtin_interfaces::msg::Time>(t);
6356
}
6457

6558
inline tf2::TimePoint fromMsg(const builtin_interfaces::msg::Time & time_msg)
6659
{
67-
int64_t d = time_msg.sec * 1000000000ull + time_msg.nanosec;
68-
std::chrono::nanoseconds ns(d);
69-
return tf2::TimePoint(std::chrono::duration_cast<tf2::Duration>(ns));
60+
return tf2::TimePointFromMsg(time_msg);
7061
}
7162

7263
inline builtin_interfaces::msg::Duration toMsg(const tf2::Duration & t)
7364
{
74-
std::chrono::nanoseconds ns =
75-
std::chrono::duration_cast<std::chrono::nanoseconds>(t);
76-
std::chrono::seconds s =
77-
std::chrono::duration_cast<std::chrono::seconds>(t);
78-
builtin_interfaces::msg::Duration duration_msg;
79-
duration_msg.sec = static_cast<int32_t>(s.count());
80-
duration_msg.nanosec = static_cast<uint32_t>(ns.count() % 1000000000ull);
81-
return duration_msg;
65+
return tf2::toMsg<tf2::Duration, builtin_interfaces::msg::Duration>(t);
8266
}
8367

8468
inline tf2::Duration fromMsg(const builtin_interfaces::msg::Duration & duration_msg)
8569
{
86-
int64_t d = duration_msg.sec * 1000000000ull + duration_msg.nanosec;
87-
std::chrono::nanoseconds ns(d);
88-
return tf2::Duration(std::chrono::duration_cast<tf2::Duration>(ns));
70+
return tf2::DurationFromMsg(duration_msg);
8971
}
9072

9173
inline double timeToSec(const builtin_interfaces::msg::Time & time_msg)

0 commit comments

Comments
 (0)