diff --git a/nav2_amcl/CMakeLists.txt b/nav2_amcl/CMakeLists.txt index 3a5836ab2d..3cb30254fa 100644 --- a/nav2_amcl/CMakeLists.txt +++ b/nav2_amcl/CMakeLists.txt @@ -2,90 +2,136 @@ cmake_minimum_required(VERSION 3.5) project(nav2_amcl) find_package(ament_cmake REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(message_filters REQUIRED) +find_package(nav_msgs REQUIRED) find_package(nav2_common REQUIRED) +find_package(nav2_msgs REQUIRED) +find_package(nav2_util REQUIRED) +find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) -find_package(rclcpp_lifecycle REQUIRED) find_package(rclcpp_components REQUIRED) -find_package(message_filters REQUIRED) -find_package(tf2_geometry_msgs REQUIRED) -find_package(geometry_msgs REQUIRED) -find_package(nav_msgs REQUIRED) +find_package(rclcpp_lifecycle REQUIRED) find_package(sensor_msgs REQUIRED) find_package(std_srvs REQUIRED) -find_package(tf2_ros REQUIRED) find_package(tf2 REQUIRED) -find_package(nav2_util REQUIRED) -find_package(nav2_msgs REQUIRED) -find_package(pluginlib REQUIRED) +find_package(tf2_geometry_msgs REQUIRED) +find_package(tf2_ros REQUIRED) nav2_package() -include_directories( - include -) - include(CheckSymbolExists) check_symbol_exists(drand48 stdlib.h HAVE_DRAND48) -add_subdirectory(src/pf) -add_subdirectory(src/map) -add_subdirectory(src/motion_model) -add_subdirectory(src/sensors) +if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wno-gnu-folding-constant) +endif() -set(executable_name amcl) +add_library(pf_lib SHARED + src/pf/pf.c + src/pf/pf_kdtree.c + src/pf/pf_pdf.c + src/pf/pf_vector.c + src/pf/eig3.c + src/pf/pf_draw.c +) +target_include_directories(pf_lib + PUBLIC + "$" + "$") +if(HAVE_DRAND48) + target_compile_definitions(pf_lib PRIVATE "HAVE_DRAND48") +endif() -add_executable(${executable_name} - src/main.cpp +add_library(map_lib SHARED + src/map/map.c + src/map/map_range.c + src/map/map_draw.c + src/map/map_cspace.cpp +) +target_include_directories(map_lib + PUBLIC + "$" + "$") + +add_library(motions_lib SHARED + src/motion_model/omni_motion_model.cpp + src/motion_model/differential_motion_model.cpp +) +target_include_directories(motions_lib + PUBLIC + "$" + "$") +target_link_libraries(motions_lib PUBLIC + pf_lib + pluginlib::pluginlib + nav2_util::nav2_util_core +) + +add_library(sensors_lib SHARED + src/sensors/laser/laser.cpp + src/sensors/laser/beam_model.cpp + src/sensors/laser/likelihood_field_model.cpp + src/sensors/laser/likelihood_field_model_prob.cpp +) +target_include_directories(sensors_lib + PUBLIC + "$" + "$") +target_link_libraries(sensors_lib PUBLIC + pf_lib + map_lib ) +set(executable_name amcl) + set(library_name ${executable_name}_core) add_library(${library_name} SHARED src/amcl_node.cpp ) - -target_include_directories(${library_name} PRIVATE src/include) - if(HAVE_DRAND48) target_compile_definitions(${library_name} PRIVATE "HAVE_DRAND48") endif() - -set(dependencies - rclcpp - rclcpp_lifecycle - rclcpp_components - message_filters - tf2_geometry_msgs - geometry_msgs - nav_msgs - sensor_msgs - std_srvs - tf2_ros - tf2 - nav2_util - nav2_msgs - pluginlib +target_include_directories(${library_name} + PUBLIC + "$" + "$") +target_link_libraries(${library_name} PUBLIC + ${geometry_msgs_TARGETS} + message_filters::message_filters + nav2_util::nav2_util_core + ${sensor_msgs_TARGETS} + ${std_srvs_TARGETS} + pluginlib::pluginlib + sensors_lib + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + ${nav_msgs_TARGETS} + tf2_ros::tf2_ros + tf2::tf2 + ${nav2_msgs_TARGETS} ) - -ament_target_dependencies(${executable_name} - ${dependencies} +target_link_libraries(${library_name} PRIVATE + rclcpp_components::component + tf2_geometry_msgs::tf2_geometry_msgs ) -target_link_libraries(${executable_name} - ${library_name} -) - -ament_target_dependencies(${library_name} - ${dependencies} +add_executable(${executable_name} + src/main.cpp ) - -target_link_libraries(${library_name} - map_lib pf_lib sensors_lib +target_include_directories(${executable_name} + PUBLIC + "$" + "$") +target_link_libraries(${executable_name} PRIVATE + ${library_name} ) rclcpp_components_register_nodes(${library_name} "nav2_amcl::AmclNode") -install(TARGETS ${library_name} +install(TARGETS ${library_name} pf_lib map_lib motions_lib sensors_lib + EXPORT ${library_name} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin @@ -96,7 +142,7 @@ install(TARGETS ${executable_name} ) install(DIRECTORY include/ - DESTINATION include/ + DESTINATION include/${PROJECT_NAME} ) if(BUILD_TESTING) @@ -104,11 +150,26 @@ if(BUILD_TESTING) # the following line skips the linter which checks for copyrights set(ament_cmake_copyright_FOUND TRUE) set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() endif() -ament_export_include_directories(include) +ament_export_include_directories("include/${PROJECT_NAME}") ament_export_libraries(${library_name} pf_lib sensors_lib motions_lib map_lib) -ament_export_dependencies(${dependencies}) +ament_export_dependencies( + geometry_msgs + message_filters + nav_msgs + nav2_msgs + nav2_util + pluginlib + rclcpp + rclcpp_lifecycle + sensor_msgs + std_srvs + tf2 + tf2_ros +) +ament_export_targets(${library_name}) pluginlib_export_plugin_description_file(nav2_amcl plugins.xml) ament_package() diff --git a/nav2_amcl/include/nav2_amcl/amcl_node.hpp b/nav2_amcl/include/nav2_amcl/amcl_node.hpp index 514bba4c55..d8f35b5c7f 100644 --- a/nav2_amcl/include/nav2_amcl/amcl_node.hpp +++ b/nav2_amcl/include/nav2_amcl/amcl_node.hpp @@ -37,17 +37,13 @@ #include "nav2_msgs/msg/particle_cloud.hpp" #include "nav2_msgs/srv/set_initial_pose.hpp" #include "nav_msgs/srv/set_map.hpp" +#include "pluginlib/class_loader.hpp" +#include "rclcpp/node_options.hpp" #include "sensor_msgs/msg/laser_scan.hpp" #include "std_srvs/srv/empty.hpp" +#include "tf2_ros/message_filter.h" #include "tf2_ros/transform_broadcaster.h" #include "tf2_ros/transform_listener.h" -#include "pluginlib/class_loader.hpp" - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-parameter" -#pragma GCC diagnostic ignored "-Wreorder" -#include "tf2_ros/message_filter.h" -#pragma GCC diagnostic pop #define NEW_UNIFORM_SAMPLING 1 diff --git a/nav2_amcl/include/nav2_amcl/angleutils.hpp b/nav2_amcl/include/nav2_amcl/angleutils.hpp index 84de30f78d..a2f489952a 100644 --- a/nav2_amcl/include/nav2_amcl/angleutils.hpp +++ b/nav2_amcl/include/nav2_amcl/angleutils.hpp @@ -22,7 +22,7 @@ #ifndef NAV2_AMCL__ANGLEUTILS_HPP_ #define NAV2_AMCL__ANGLEUTILS_HPP_ -#include +#include namespace nav2_amcl { diff --git a/nav2_amcl/include/nav2_amcl/motion_model/differential_motion_model.hpp b/nav2_amcl/include/nav2_amcl/motion_model/differential_motion_model.hpp index 2d17360204..5780c84b20 100644 --- a/nav2_amcl/include/nav2_amcl/motion_model/differential_motion_model.hpp +++ b/nav2_amcl/include/nav2_amcl/motion_model/differential_motion_model.hpp @@ -22,11 +22,9 @@ #ifndef NAV2_AMCL__MOTION_MODEL__DIFFERENTIAL_MOTION_MODEL_HPP_ #define NAV2_AMCL__MOTION_MODEL__DIFFERENTIAL_MOTION_MODEL_HPP_ -#include -#include -#include #include "nav2_amcl/motion_model/motion_model.hpp" -#include "nav2_amcl/angleutils.hpp" +#include "nav2_amcl/pf/pf.hpp" +#include "nav2_amcl/pf/pf_vector.hpp" namespace nav2_amcl diff --git a/nav2_amcl/include/nav2_amcl/motion_model/motion_model.hpp b/nav2_amcl/include/nav2_amcl/motion_model/motion_model.hpp index 4cd1c6a879..55a8ac2fcd 100644 --- a/nav2_amcl/include/nav2_amcl/motion_model/motion_model.hpp +++ b/nav2_amcl/include/nav2_amcl/motion_model/motion_model.hpp @@ -17,11 +17,8 @@ #ifndef NAV2_AMCL__MOTION_MODEL__MOTION_MODEL_HPP_ #define NAV2_AMCL__MOTION_MODEL__MOTION_MODEL_HPP_ -#include -#include - #include "nav2_amcl/pf/pf.hpp" -#include "nav2_amcl/pf/pf_pdf.hpp" +#include "nav2_amcl/pf/pf_vector.hpp" namespace nav2_amcl { diff --git a/nav2_amcl/include/nav2_amcl/motion_model/omni_motion_model.hpp b/nav2_amcl/include/nav2_amcl/motion_model/omni_motion_model.hpp index ae586d4d6c..e57259a3e1 100644 --- a/nav2_amcl/include/nav2_amcl/motion_model/omni_motion_model.hpp +++ b/nav2_amcl/include/nav2_amcl/motion_model/omni_motion_model.hpp @@ -22,12 +22,9 @@ #ifndef NAV2_AMCL__MOTION_MODEL__OMNI_MOTION_MODEL_HPP_ #define NAV2_AMCL__MOTION_MODEL__OMNI_MOTION_MODEL_HPP_ -#include -#include -#include #include "nav2_amcl/motion_model/motion_model.hpp" -#include "nav2_amcl/angleutils.hpp" - +#include "nav2_amcl/pf/pf.hpp" +#include "nav2_amcl/pf/pf_vector.hpp" namespace nav2_amcl { diff --git a/nav2_amcl/include/nav2_amcl/sensors/laser/laser.hpp b/nav2_amcl/include/nav2_amcl/sensors/laser/laser.hpp index edc4124128..8381e9b54b 100644 --- a/nav2_amcl/include/nav2_amcl/sensors/laser/laser.hpp +++ b/nav2_amcl/include/nav2_amcl/sensors/laser/laser.hpp @@ -18,10 +18,10 @@ #ifndef NAV2_AMCL__SENSORS__LASER__LASER_HPP_ #define NAV2_AMCL__SENSORS__LASER__LASER_HPP_ -#include +#include "nav2_amcl/map/map.hpp" #include "nav2_amcl/pf/pf.hpp" #include "nav2_amcl/pf/pf_pdf.hpp" -#include "nav2_amcl/map/map.hpp" +#include "nav2_amcl/pf/pf_vector.hpp" namespace nav2_amcl { diff --git a/nav2_amcl/package.xml b/nav2_amcl/package.xml index 8fac0f1774..38da836d08 100644 --- a/nav2_amcl/package.xml +++ b/nav2_amcl/package.xml @@ -15,27 +15,30 @@ 'amcl' Player driver.

- Mohammad Haghighipanah LGPL-2.1-or-later + Brian P. Gerkey + contradict@gmail.com + ament_cmake nav2_common - rclcpp - tf2_geometry_msgs + geometry_msgs message_filters nav_msgs + nav2_msgs + nav2_util + pluginlib + rclcpp + rclcpp_components + rclcpp_lifecycle sensor_msgs std_srvs - tf2_ros tf2 - nav2_util - nav2_msgs - launch_ros - launch_testing - pluginlib + tf2_geometry_msgs + tf2_ros + ament_lint_common ament_lint_auto diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp index b5e512ba94..5c6b165d59 100644 --- a/nav2_amcl/src/amcl_node.cpp +++ b/nav2_amcl/src/amcl_node.cpp @@ -34,7 +34,9 @@ #include "nav2_amcl/pf/pf.hpp" #include "nav2_util/string_utils.hpp" #include "nav2_amcl/sensors/laser/laser.hpp" +#include "rclcpp/node_options.hpp" #include "tf2/convert.h" +#include "tf2/utils.h" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "tf2/LinearMath/Transform.h" #include "tf2_ros/buffer.h" @@ -43,15 +45,9 @@ #include "tf2_ros/transform_listener.h" #include "tf2_ros/create_timer_ros.h" -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wpedantic" -#include "tf2/utils.h" -#pragma GCC diagnostic pop - #include "nav2_amcl/portable_utils.hpp" #include "nav2_util/validate_messages.hpp" -using namespace std::placeholders; using rcl_interfaces::msg::ParameterType; using namespace std::chrono_literals; @@ -1571,15 +1567,18 @@ AmclNode::initServices() { global_loc_srv_ = create_service( "reinitialize_global_localization", - std::bind(&AmclNode::globalLocalizationCallback, this, _1, _2, _3)); + std::bind(&AmclNode::globalLocalizationCallback, this, std::placeholders::_1, + std::placeholders::_2, std::placeholders::_3)); initial_guess_srv_ = create_service( "set_initial_pose", - std::bind(&AmclNode::initialPoseReceivedSrv, this, _1, _2, _3)); + std::bind(&AmclNode::initialPoseReceivedSrv, this, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3)); nomotion_update_srv_ = create_service( "request_nomotion_update", - std::bind(&AmclNode::nomotionUpdateCallback, this, _1, _2, _3)); + std::bind(&AmclNode::nomotionUpdateCallback, this, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3)); } void diff --git a/nav2_amcl/src/map/CMakeLists.txt b/nav2_amcl/src/map/CMakeLists.txt deleted file mode 100644 index 9e965f6695..0000000000 --- a/nav2_amcl/src/map/CMakeLists.txt +++ /dev/null @@ -1,13 +0,0 @@ -add_library(map_lib SHARED - map.c - map_range.c - map_draw.c - map_cspace.cpp -) - -install(TARGETS - map_lib - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin -) diff --git a/nav2_amcl/src/map/map.c b/nav2_amcl/src/map/map.c index a4528cc663..c96c25772a 100644 --- a/nav2_amcl/src/map/map.c +++ b/nav2_amcl/src/map/map.c @@ -25,11 +25,7 @@ * CVS: $Id: map.c 1713 2003-08-23 04:03:43Z inspectorg $ **************************************************************************/ -#include -#include #include -#include -#include #include "nav2_amcl/map/map.hpp" diff --git a/nav2_amcl/src/map/map_cspace.cpp b/nav2_amcl/src/map/map_cspace.cpp index ce66baf1a5..d6c5587950 100644 --- a/nav2_amcl/src/map/map_cspace.cpp +++ b/nav2_amcl/src/map/map_cspace.cpp @@ -19,9 +19,8 @@ * */ -#include -#include -#include +#include +#include #include #include "nav2_amcl/map/map.hpp" diff --git a/nav2_amcl/src/map/map_range.c b/nav2_amcl/src/map/map_range.c index 761f216d39..5041a21e69 100644 --- a/nav2_amcl/src/map/map_range.c +++ b/nav2_amcl/src/map/map_range.c @@ -25,7 +25,6 @@ * CVS: $Id: map_range.c 1347 2003-05-05 06:24:33Z inspectorg $ **************************************************************************/ -#include #include #include #include diff --git a/nav2_amcl/src/motion_model/CMakeLists.txt b/nav2_amcl/src/motion_model/CMakeLists.txt deleted file mode 100644 index f1c2e35413..0000000000 --- a/nav2_amcl/src/motion_model/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -add_library(motions_lib SHARED - omni_motion_model.cpp - differential_motion_model.cpp -) -target_link_libraries(motions_lib pf_lib) -ament_target_dependencies(motions_lib - pluginlib - nav2_util -) - -install(TARGETS - motions_lib - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin -) diff --git a/nav2_amcl/src/motion_model/differential_motion_model.cpp b/nav2_amcl/src/motion_model/differential_motion_model.cpp index 228b66057a..afac92bb89 100644 --- a/nav2_amcl/src/motion_model/differential_motion_model.cpp +++ b/nav2_amcl/src/motion_model/differential_motion_model.cpp @@ -19,7 +19,11 @@ * */ +#include + +#include "nav2_amcl/angleutils.hpp" #include "nav2_amcl/motion_model/differential_motion_model.hpp" +#include "nav2_amcl/pf/pf_pdf.hpp" namespace nav2_amcl { diff --git a/nav2_amcl/src/motion_model/omni_motion_model.cpp b/nav2_amcl/src/motion_model/omni_motion_model.cpp index 969fb7f0d6..6190273aa3 100644 --- a/nav2_amcl/src/motion_model/omni_motion_model.cpp +++ b/nav2_amcl/src/motion_model/omni_motion_model.cpp @@ -19,7 +19,12 @@ * */ +#include + +#include "nav2_amcl/angleutils.hpp" #include "nav2_amcl/motion_model/omni_motion_model.hpp" +#include "nav2_amcl/pf/pf_pdf.hpp" +#include "nav2_amcl/pf/pf_vector.hpp" namespace nav2_amcl { diff --git a/nav2_amcl/src/pf/CMakeLists.txt b/nav2_amcl/src/pf/CMakeLists.txt deleted file mode 100644 index 3b4b2fa5ca..0000000000 --- a/nav2_amcl/src/pf/CMakeLists.txt +++ /dev/null @@ -1,25 +0,0 @@ -if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wno-gnu-folding-constant) -endif() - -add_library(pf_lib SHARED - pf.c - pf_kdtree.c - pf_pdf.c - pf_vector.c - eig3.c - pf_draw.c -) - -target_include_directories(pf_lib PRIVATE ../include) -if(HAVE_DRAND48) - target_compile_definitions(pf_lib PRIVATE "HAVE_DRAND48") -endif() -target_link_libraries(pf_lib m) - -install(TARGETS - pf_lib - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin -) diff --git a/nav2_amcl/src/sensors/CMakeLists.txt b/nav2_amcl/src/sensors/CMakeLists.txt deleted file mode 100644 index e105675cbf..0000000000 --- a/nav2_amcl/src/sensors/CMakeLists.txt +++ /dev/null @@ -1,15 +0,0 @@ -add_library(sensors_lib SHARED - laser/laser.cpp - laser/beam_model.cpp - laser/likelihood_field_model.cpp - laser/likelihood_field_model_prob.cpp -) -# map_update_cspace -target_link_libraries(sensors_lib pf_lib map_lib) - -install(TARGETS - sensors_lib - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin -) diff --git a/nav2_amcl/src/sensors/laser/laser.cpp b/nav2_amcl/src/sensors/laser/laser.cpp index 9059179874..2f7050efad 100644 --- a/nav2_amcl/src/sensors/laser/laser.cpp +++ b/nav2_amcl/src/sensors/laser/laser.cpp @@ -19,10 +19,7 @@ * */ -#include -#include -#include -#include +#include #include "nav2_amcl/sensors/laser/laser.hpp" diff --git a/nav2_amcl/src/sensors/laser/likelihood_field_model.cpp b/nav2_amcl/src/sensors/laser/likelihood_field_model.cpp index 1148c2828d..a8e3b7a1f6 100644 --- a/nav2_amcl/src/sensors/laser/likelihood_field_model.cpp +++ b/nav2_amcl/src/sensors/laser/likelihood_field_model.cpp @@ -19,8 +19,8 @@ * */ -#include -#include +#include +#include #include "nav2_amcl/sensors/laser/laser.hpp" diff --git a/nav2_amcl/src/sensors/laser/likelihood_field_model_prob.cpp b/nav2_amcl/src/sensors/laser/likelihood_field_model_prob.cpp index 99efa793f8..ce9dc0331e 100644 --- a/nav2_amcl/src/sensors/laser/likelihood_field_model_prob.cpp +++ b/nav2_amcl/src/sensors/laser/likelihood_field_model_prob.cpp @@ -19,9 +19,8 @@ * */ - -#include -#include +#include +#include #include "nav2_amcl/sensors/laser/laser.hpp" diff --git a/nav2_map_server/CMakeLists.txt b/nav2_map_server/CMakeLists.txt index 3c2ce2eef8..c193685363 100644 --- a/nav2_map_server/CMakeLists.txt +++ b/nav2_map_server/CMakeLists.txt @@ -166,7 +166,7 @@ if(BUILD_TESTING) add_subdirectory(test) endif() -ament_export_include_directories(include) +ament_export_include_directories("include/${PROJECT_NAME}") ament_export_libraries( ${library_name} ${map_io_library_name} diff --git a/nav2_voxel_grid/CMakeLists.txt b/nav2_voxel_grid/CMakeLists.txt index afd87f59af..e204367ada 100644 --- a/nav2_voxel_grid/CMakeLists.txt +++ b/nav2_voxel_grid/CMakeLists.txt @@ -43,7 +43,7 @@ if(BUILD_TESTING) endif() ament_export_dependencies(rclcpp) -ament_export_include_directories(include) +ament_export_include_directories("include/${PROJECT_NAME}") ament_export_libraries(voxel_grid) ament_export_targets(voxel_grid)