Skip to content

Commit 8edc978

Browse files
Merge pull request #528 from Team488/fix_ros2_windows
Fix unresolved rclcpp operator+
2 parents 3d052fd + 865584a commit 8edc978

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

src/ros_filter.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1832,7 +1832,7 @@ void RosFilter<T>::periodicUpdate()
18321832

18331833
if (getFilteredOdometryMessage(filtered_position)) {
18341834
world_base_link_trans_msg_.header.stamp =
1835-
tf_time_offset_ + filtered_position.header.stamp;
1835+
static_cast<rclcpp::Time>(filtered_position.header.stamp) + tf_time_offset_;
18361836
world_base_link_trans_msg_.header.frame_id =
18371837
filtered_position.header.frame_id;
18381838
world_base_link_trans_msg_.child_frame_id =
@@ -1895,7 +1895,7 @@ void RosFilter<T>::periodicUpdate()
18951895
geometry_msgs::msg::TransformStamped map_odom_trans_msg;
18961896
map_odom_trans_msg.transform = tf2::toMsg(map_odom_trans);
18971897
map_odom_trans_msg.header.stamp =
1898-
tf_time_offset_ + filtered_position.header.stamp;
1898+
static_cast<rclcpp::Time>(filtered_position.header.stamp) + tf_time_offset_;
18991899
map_odom_trans_msg.header.frame_id = map_frame_id_;
19001900
map_odom_trans_msg.child_frame_id = odom_frame_id_;
19011901

0 commit comments

Comments
 (0)