Skip to content

Commit eba25c3

Browse files
committed
Remove boost from fiducial_slam
1 parent 3c9246a commit eba25c3

File tree

2 files changed

+3
-13
lines changed

2 files changed

+3
-13
lines changed

fiducial_slam/CMakeLists.txt

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -23,10 +23,6 @@ find_package(builtin_interfaces REQUIRED)
2323
find_package(rosidl_default_generators REQUIRED)
2424

2525
find_package(OpenCV REQUIRED)
26-
find_package(Boost REQUIRED COMPONENTS
27-
filesystem
28-
)
29-
3026

3127
set(DEPENDENCIES
3228
rclcpp
@@ -60,7 +56,7 @@ add_executable(fiducial_slam_node #TODO ROS2PORT should be "fiducial_slam" but t
6056
src/transform_with_variance.cpp
6157
src/observation.cpp)
6258

63-
target_link_libraries(fiducial_slam_node ${Boost_LIBRARIES})
59+
target_link_libraries(fiducial_slam_node)
6460

6561
ament_target_dependencies(fiducial_slam_node ${DEPENDENCIES} OpenCV)
6662

@@ -81,6 +77,8 @@ install(FILES fiducials.rviz
8177
DESTINATION share/${PROJECT_NAME}
8278
)
8379

80+
install(DIRECTORY DESTINATION $ENV{HOME}/.ros/slam)
81+
8482
###########
8583
## Tests ##
8684
###########

fiducial_slam/src/map.cpp

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -44,9 +44,6 @@
4444
#include <geometry_msgs/msg/transform_stamped.hpp>
4545
#include <visualization_msgs/msg/marker.hpp>
4646

47-
#include <boost/filesystem.hpp>
48-
49-
5047
static double systematic_error = 0.01;
5148

5249
// Update a fiducial position in map with a new estimate
@@ -123,11 +120,6 @@ Map::Map(rclcpp::Node::SharedPtr &nh)
123120
multiErrorThreshold = nh->declare_parameter("multi_error_theshold", -1.0);
124121
mapFilename = nh->declare_parameter("map_file", std::string(getenv("HOME")) + "/.ros/slam/map.txt");
125122

126-
127-
boost::filesystem::path mapPath(mapFilename);
128-
boost::filesystem::path dir = mapPath.parent_path();
129-
boost::filesystem::create_directories(dir);
130-
131123
std::string initialMap;
132124
initialMap = nh->declare_parameter("initial_map_file", "");
133125

0 commit comments

Comments
 (0)