Skip to content

Commit

Permalink
support rolling on jammy (SteveMacenski#494)
Browse files Browse the repository at this point in the history
* support rolling on jammy

Signed-off-by: wep21 <[email protected]>

* remove backward support

Signed-off-by: wep21 <[email protected]>

* change upper and lower case letters for SuiteSparse library

Signed-off-by: wep21 <[email protected]>
  • Loading branch information
wep21 authored May 19, 2022
1 parent edcfffd commit 3010d46
Show file tree
Hide file tree
Showing 6 changed files with 12 additions and 9 deletions.
File renamed without changes.
2 changes: 1 addition & 1 deletion CMake/FindCSparse.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -21,5 +21,5 @@ FIND_LIBRARY(CSPARSE_LIBRARY NAMES cxsparse
)

include(FindPackageHandleStandardArgs)
find_package_handle_standard_args(CSPARSE DEFAULT_MSG
find_package_handle_standard_args(CSparse DEFAULT_MSG
CSPARSE_INCLUDE_DIR CSPARSE_LIBRARY)
11 changes: 7 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,9 @@ set(libraries

find_package(PkgConfig REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(CHOLMOD REQUIRED)
find_package(CSparse REQUIRED)
find_package(G2O REQUIRED)
find_package(Cholmod REQUIRED)
find_package(LAPACK REQUIRED)
find_package(Ceres REQUIRED COMPONENTS SuiteSparse)

Expand Down Expand Up @@ -119,7 +119,8 @@ target_include_directories(SlamToolboxPlugin PUBLIC
${OGRE_INCLUDE_DIRS}
)
target_link_libraries(SlamToolboxPlugin ${QT_LIBRARIES} rviz_common::rviz_common)
rosidl_target_interfaces(SlamToolboxPlugin ${PROJECT_NAME} "rosidl_typesupport_cpp")
rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
target_link_libraries(SlamToolboxPlugin "${cpp_typesupport_target}")
target_compile_definitions(SlamToolboxPlugin PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
target_compile_definitions(SlamToolboxPlugin PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY")
pluginlib_export_plugin_description_file(rviz_common rviz_plugins.xml)
Expand All @@ -132,7 +133,8 @@ target_link_libraries(ceres_solver_plugin ${CERES_LIBRARIES}
${TBB_LIBRARIES}
kartoSlamToolbox
)
rosidl_target_interfaces(ceres_solver_plugin ${PROJECT_NAME} "rosidl_typesupport_cpp")
rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
target_link_libraries(ceres_solver_plugin "${cpp_typesupport_target}")
pluginlib_export_plugin_description_file(slam_toolbox solver_plugins.xml)

#### Tool lib for mapping
Expand All @@ -141,7 +143,8 @@ ament_target_dependencies(toolbox_common
${dependencies}
)
target_link_libraries(toolbox_common kartoSlamToolbox ${Boost_LIBRARIES})
rosidl_target_interfaces(toolbox_common ${PROJECT_NAME} "rosidl_typesupport_cpp")
rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
target_link_libraries(toolbox_common "${cpp_typesupport_target}")

#### Mapping executibles
add_library(async_slam_toolbox src/slam_toolbox_async.cpp)
Expand Down
4 changes: 2 additions & 2 deletions lib/karto_sdk/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(Boost REQUIRED system serialization filesystem thread)
find_package(TBB REQUIRED)
find_package(TBB REQUIRED NO_CMAKE_PACKAGE_REGISTRY)

set(dependencies
rclcpp
Expand All @@ -29,7 +29,7 @@ add_definitions(${EIGEN3_DEFINITIONS})
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})
target_link_libraries(kartoSlamToolbox ${Boost_LIBRARIES} TBB::tbb)

install(DIRECTORY include/
DESTINATION include/
Expand Down
2 changes: 1 addition & 1 deletion lib/karto_sdk/include/karto_sdk/Mapper.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
#include <utility>
#include <string>

#include "tbb/parallel_do.h"
#include "tbb/parallel_for_each.h"
#include "tbb/parallel_for.h"
#include "tbb/blocked_range.h"

Expand Down
2 changes: 1 addition & 1 deletion lib/karto_sdk/src/Mapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -770,7 +770,7 @@ kt_double ScanMatcher::CorrelateScan(
m_nAngles = nAngles;
m_searchAngleResolution = searchAngleResolution;
m_doPenalize = doPenalize;
tbb::parallel_do(m_yPoses, (*this) );
tbb::parallel_for_each(m_yPoses, (*this));

// find value of best response (in [0; 1])
kt_double bestResponse = -1;
Expand Down

0 comments on commit 3010d46

Please sign in to comment.