Skip to content

Commit f323393

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

File tree

2 files changed

+2
-8
lines changed

2 files changed

+2
-8
lines changed

fiducial_slam/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -81,6 +81,8 @@ install(FILES fiducials.rviz
8181
DESTINATION share/${PROJECT_NAME}
8282
)
8383

84+
install(DIRECTORY DESTINATION $ENV{HOME}/.ros/slam)
85+
8486
###########
8587
## Tests ##
8688
###########

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)