Skip to content

Commit

Permalink
fix deprecated rclcpp:::Duration warning
Browse files Browse the repository at this point in the history
  • Loading branch information
alonfaraj committed May 19, 2022
1 parent 94c6aa1 commit c8241d1
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -682,7 +682,7 @@ sensor_msgs::msg::PointCloud2 AirsimROSWrapper::get_lidar_msg_from_airsim(const
if (isENU_) {
try {
sensor_msgs::msg::PointCloud2 lidar_msg_enu;
auto transformStampedENU = tf_buffer_->lookupTransform(AIRSIM_FRAME_ID, vehicle_name, rclcpp::Time(0), rclcpp::Duration(1));
auto transformStampedENU = tf_buffer_->lookupTransform(AIRSIM_FRAME_ID, vehicle_name, rclcpp::Time(0), rclcpp::Duration::from_nanoseconds(1));
tf2::doTransform(lidar_msg, lidar_msg_enu, transformStampedENU);

lidar_msg_enu.header.stamp = lidar_msg.header.stamp;
Expand Down

0 comments on commit c8241d1

Please sign in to comment.