Skip to content

Commit

Permalink
Fixed error in relative imports. (#472)
Browse files Browse the repository at this point in the history
  • Loading branch information
dimasad authored Jan 28, 2022
1 parent fab61e1 commit f449abf
Show file tree
Hide file tree
Showing 6 changed files with 9 additions and 11 deletions.
3 changes: 2 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,8 @@ set(CMAKE_INCLUDE_CURRENT_DIR ON)
add_definitions(-DQT_NO_KEYWORDS)
find_package(Boost REQUIRED system serialization filesystem thread)

include_directories(include ${EIGEN3_INCLUDE_DIRS}
include_directories(include lib/karto_sdk/include
${EIGEN3_INCLUDE_DIRS}
${CHOLMOD_INCLUDE_DIR}
${Boost_INCLUDE_DIRS}
${TBB_INCLUDE_DIRS}
Expand Down
2 changes: 1 addition & 1 deletion include/slam_toolbox/get_pose_helper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <string>
#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
#include "slam_toolbox/toolbox_types.hpp"
#include "../lib/karto_sdk/include/karto_sdk/Mapper.h"
#include "karto_sdk/Mapper.h"

namespace pose_utils
{
Expand Down
2 changes: 1 addition & 1 deletion include/slam_toolbox/serialization.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include <vector>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "../lib/karto_sdk/include/karto_sdk/Mapper.h"
#include "karto_sdk/Mapper.h"

namespace serialization
{
Expand Down
3 changes: 1 addition & 2 deletions include/slam_toolbox/toolbox_types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,7 @@
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
#include "tf2/transform_datatypes.h"

// god... getting this to work in ROS2 was a real pain
#include "../lib/karto_sdk/include/karto_sdk/Mapper.h"
#include "karto_sdk/Mapper.h"
#include "slam_toolbox/toolbox_msgs.hpp"

// compute linear index for given map coords
Expand Down
5 changes: 2 additions & 3 deletions lib/karto_sdk/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,16 +18,15 @@ set(dependencies
rclcpp
)

include_directories(include ${catkin_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
include_directories(include ${EIGEN3_INCLUDE_DIRS}
${Boost_INCLUDE_DIR}
${BOOST_INCLUDE_DIRS}
${TBB_INCLUDE_DIRS}
)

add_definitions(${EIGEN3_DEFINITIONS})

include_directories(include ${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS} ${TBB_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
include_directories(include ${EIGEN3_INCLUDE_DIRS} ${TBB_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
add_library(kartoSlamToolbox SHARED src/Karto.cpp src/Mapper.cpp)
ament_target_dependencies(kartoSlamToolbox ${dependencies})
target_link_libraries(kartoSlamToolbox ${Boost_LIBRARIES} ${TBB_LIBRARIES})
Expand Down
5 changes: 2 additions & 3 deletions solvers/ceres_solver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,13 +13,12 @@
#include <unordered_map>
#include <utility>
#include <cmath>
// god... getting this to work in ROS2 was a real pain
#include "../lib/karto_sdk/include/karto_sdk/Mapper.h"
#include "karto_sdk/Mapper.h"
#include "solvers/ceres_utils.h"

#include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/empty.hpp"
#include "../include/slam_toolbox/toolbox_types.hpp"
#include "slam_toolbox/toolbox_types.hpp"

namespace solver_plugins
{
Expand Down

0 comments on commit f449abf

Please sign in to comment.