Skip to content

Commit e9da267

Browse files
authored
Replaced deprecated rcpputils::path (#10)
Signed-off-by: Alejandro Hernandez Cordero <[email protected]>
1 parent f376655 commit e9da267

File tree

2 files changed

+5
-3
lines changed

2 files changed

+5
-3
lines changed

CMakeLists.txt

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,6 @@ find_package(ament_cmake_ros REQUIRED)
1616

1717
find_package(point_cloud_transport REQUIRED)
1818
find_package(rclcpp REQUIRED)
19-
find_package(rcpputils REQUIRED)
2019
find_package(rosbag2_cpp REQUIRED)
2120
find_package(sensor_msgs REQUIRED)
2221

@@ -30,7 +29,7 @@ ament_target_dependencies(encoder_test point_cloud_transport rosbag2_cpp sensor_
3029

3130
# publisher
3231
add_executable(publisher_test src/my_publisher.cpp)
33-
ament_target_dependencies(publisher_test point_cloud_transport rclcpp rcpputils rosbag2_cpp sensor_msgs)
32+
ament_target_dependencies(publisher_test point_cloud_transport rclcpp rosbag2_cpp sensor_msgs)
3433

3534
# subscriber
3635
add_executable(subscriber_test src/my_subscriber.cpp)

src/my_publisher.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,9 @@
2929

3030

3131
#include <iostream>
32+
#include <filesystem>
33+
#include <memory>
34+
#include <string>
3235

3336
// for reading rosbag
3437
#include <ament_index_cpp/get_package_share_directory.hpp>
@@ -60,7 +63,7 @@ int main(int argc, char ** argv)
6063
bag_file = argv[1];
6164
}
6265

63-
if (!rcpputils::fs::exists(bag_file)) {
66+
if (!std::filesystem::exists(bag_file)) {
6467
std::cout << "Not able to open file [" << bag_file << "]" << '\n';
6568
return -1;
6669
}

0 commit comments

Comments
 (0)