Skip to content

Commit

Permalink
Remove boost from fiducial_slam
Browse files Browse the repository at this point in the history
  • Loading branch information
agutenkunst committed Sep 12, 2021
1 parent 3c9246a commit f323393
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 8 deletions.
2 changes: 2 additions & 0 deletions fiducial_slam/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,8 @@ install(FILES fiducials.rviz
DESTINATION share/${PROJECT_NAME}
)

install(DIRECTORY DESTINATION $ENV{HOME}/.ros/slam)

###########
## Tests ##
###########
Expand Down
8 changes: 0 additions & 8 deletions fiducial_slam/src/map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,6 @@
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <visualization_msgs/msg/marker.hpp>

#include <boost/filesystem.hpp>


static double systematic_error = 0.01;

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


boost::filesystem::path mapPath(mapFilename);
boost::filesystem::path dir = mapPath.parent_path();
boost::filesystem::create_directories(dir);

std::string initialMap;
initialMap = nh->declare_parameter("initial_map_file", "");

Expand Down

0 comments on commit f323393

Please sign in to comment.