diff --git a/nav2_amcl/include/nav2_amcl/amcl_node.hpp b/nav2_amcl/include/nav2_amcl/amcl_node.hpp index 96dbf63ed5e950e9d130f47822b2d75fbe78e59f..59a41b960b3f5dceb9d2f73dac4b1c109d29aac0 100644 --- a/nav2_amcl/include/nav2_amcl/amcl_node.hpp +++ b/nav2_amcl/include/nav2_amcl/amcl_node.hpp @@ -212,7 +212,6 @@ private: std::string robot_model_type_; std::string sensor_model_type_; - std::chrono::duration<double> cloud_pub_interval; // Time for tolerance on the published transform, // basically defines how long a map->odom transform is good for @@ -226,7 +225,6 @@ private: amcl_hyp_t * initial_pose_hyp_; bool first_map_received_; - bool first_reconfigure_call_; std::recursive_mutex configuration_mutex_; diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp index 477a66b384715b8bef99eaeaa55917e6a1f165c5..ca529c728f4b1345236e57802ad670faa45ecfa9 100644 --- a/nav2_amcl/src/amcl_node.cpp +++ b/nav2_amcl/src/amcl_node.cpp @@ -78,8 +78,7 @@ AmclNode::AmclNode() motionModel_(NULL), laser_(NULL), initial_pose_hyp_(NULL), - first_map_received_(false), - first_reconfigure_call_(true) + first_map_received_(false) { RCLCPP_INFO(get_logger(), "Initializing AMCL"); std::lock_guard<std::recursive_mutex> l(configuration_mutex_); diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp index d9829dba03b4d1a6611b81c6e0b4edae19d3bbf3..7ecd8630ae42b6878bac9f26e90f03344d4520a1 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp @@ -55,7 +55,6 @@ private: // Clearing parameters unsigned char reset_value_; - double reset_distance_; std::vector<std::string> clearable_layers_; // Server for clearing the costmap diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp index 7a9bba2ea989479d7337068872164edceda3303c..b4a784603e2aeef0b64daf717a3ba603beb0e569 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp @@ -474,9 +474,9 @@ private: { public: PolygonOutlineCells( - const Costmap2D & costmap, const unsigned char * char_map, + const Costmap2D & costmap, const unsigned char * /*char_map*/, std::vector<MapLocation> & cells) - : costmap_(costmap), char_map_(char_map), cells_(cells) + : costmap_(costmap), cells_(cells) { } @@ -490,7 +490,6 @@ public: private: const Costmap2D & costmap_; - const unsigned char * char_map_; std::vector<MapLocation> & cells_; }; }; diff --git a/nav2_costmap_2d/src/observation_buffer.cpp b/nav2_costmap_2d/src/observation_buffer.cpp index 12b460e9962e077dee81bd1916999bcdc0ba3f31..2c7b1112ac1775b2621393632fa6231c2efb6020 100644 --- a/nav2_costmap_2d/src/observation_buffer.cpp +++ b/nav2_costmap_2d/src/observation_buffer.cpp @@ -248,7 +248,7 @@ bool ObservationBuffer::isCurrent() const "nav2_costmap_2d"), "The %s observation buffer has not been updated for %.2f seconds, and it should be updated every %.2f seconds.", //NOLINT topic_name_.c_str(), - (nh_->now() - last_updated_), expected_update_rate_); + (nh_->now() - last_updated_).seconds(), expected_update_rate_.seconds()); } return current; } diff --git a/nav2_dwb_controller/dwb_core/src/dwb_core.cpp b/nav2_dwb_controller/dwb_core/src/dwb_core.cpp index 5ce18e59a8229580ae4173c5b3d8a170973629e4..b30be1b90192f42c7cb62615ee9fd9b6e1a0f985 100644 --- a/nav2_dwb_controller/dwb_core/src/dwb_core.cpp +++ b/nav2_dwb_controller/dwb_core/src/dwb_core.cpp @@ -102,13 +102,13 @@ void DWBLocalPlanner::initialize( std::string traj_generator_name; nh_->get_parameter_or("trajectory_generator_name", traj_generator_name, std::string("dwb_plugins::StandardTrajectoryGenerator")); - traj_generator_ = std::move(traj_gen_loader_.createUniqueInstance(traj_generator_name)); + traj_generator_ = traj_gen_loader_.createUniqueInstance(traj_generator_name); traj_generator_->initialize(nh_); std::string goal_checker_name; nh_->get_parameter_or("goal_checker_name", goal_checker_name, std::string("dwb_plugins::SimpleGoalChecker")); - goal_checker_ = std::move(goal_checker_loader_.createUniqueInstance(goal_checker_name)); + goal_checker_ = goal_checker_loader_.createUniqueInstance(goal_checker_name); goal_checker_->initialize(nh_); loadCritics(); @@ -150,7 +150,7 @@ void DWBLocalPlanner::loadCritics() nh_->get_parameter_or(plugin_name + "/class", plugin_class, plugin_name); plugin_class = resolveCriticClassName(plugin_class); - TrajectoryCritic::Ptr plugin = std::move(critic_loader_.createUniqueInstance(plugin_class)); + TrajectoryCritic::Ptr plugin = critic_loader_.createUniqueInstance(plugin_class); RCLCPP_INFO(nh_->get_logger(), "Using critic \"%s\" (%s)", plugin_name.c_str(), plugin_class.c_str()); critics_.push_back(plugin); diff --git a/nav2_dwb_controller/dwb_critics/include/dwb_critics/map_grid.hpp b/nav2_dwb_controller/dwb_critics/include/dwb_critics/map_grid.hpp index 7afe1b54e7056ab8a73c9b888c2a7ea8c2dd6734..061da1ba3cabf3adf915fc9fd3d646073386c740 100644 --- a/nav2_dwb_controller/dwb_critics/include/dwb_critics/map_grid.hpp +++ b/nav2_dwb_controller/dwb_critics/include/dwb_critics/map_grid.hpp @@ -109,6 +109,7 @@ protected: public: MapGridQueue(nav2_costmap_2d::Costmap2D & costmap, MapGridCritic & parent) : costmap_queue::CostmapQueue(costmap, true), parent_(parent) {} + virtual ~MapGridQueue() = default; bool validCellToQueue(const costmap_queue::CellData & cell) override; protected: @@ -118,7 +119,7 @@ protected: /** * @brief Clear the queuDWB_CRITICS_MAP_GRID_He and set cell_values_ to the appropriate number of unreachableCellScore */ - void reset(); + void reset() override; /** * @brief Go through the queue and set the cells to the Manhattan distance from their parents diff --git a/nav2_dynamic_params/include/nav2_dynamic_params/dynamic_params_client.hpp b/nav2_dynamic_params/include/nav2_dynamic_params/dynamic_params_client.hpp index 13d46397cdc97db0c26f81a07f824c7c1389863a..1a07c83c47ff279daa324ecb8a2706436cda2600 100644 --- a/nav2_dynamic_params/include/nav2_dynamic_params/dynamic_params_client.hpp +++ b/nav2_dynamic_params/include/nav2_dynamic_params/dynamic_params_client.hpp @@ -358,7 +358,7 @@ private: bool get_param_from_map(const std::string & name, T & value) { if (dynamic_param_map_.count(name) > 0 && - !dynamic_param_map_[name].get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET) + !(dynamic_param_map_[name].get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET)) { value = dynamic_param_map_[name].get_value<T>(); return true; diff --git a/nav2_motion_primitives/src/spin.cpp b/nav2_motion_primitives/src/spin.cpp index ffc2c1cb63e7e1ee62d31bf996c4d87a1a4465c8..ff93e7b29716b71ae1c0b4f5f65204f6a2333535 100644 --- a/nav2_motion_primitives/src/spin.cpp +++ b/nav2_motion_primitives/src/spin.cpp @@ -20,6 +20,7 @@ #include <memory> #include "nav2_motion_primitives/spin.hpp" +#pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wpedantic" #include "tf2/utils.h" #pragma GCC diagnostic pop diff --git a/nav2_tasks/include/nav2_tasks/task_server.hpp b/nav2_tasks/include/nav2_tasks/task_server.hpp index 417ea9367129bd25c5d707e3bc7ba83854f70e77..90b571b9a105d185e029397daca0d2a8bfb2ee33 100644 --- a/nav2_tasks/include/nav2_tasks/task_server.hpp +++ b/nav2_tasks/include/nav2_tasks/task_server.hpp @@ -57,7 +57,7 @@ public: resultPub_ = node_->create_publisher<ResultMsg>(taskName + "_result"); statusPub_ = node_->create_publisher<StatusMsg>(taskName + "_status"); - execute_callback_ = [this](const typename CommandMsg::SharedPtr) { + execute_callback_ = [](const typename CommandMsg::SharedPtr) { printf("Execute callback not set!\n"); return TaskStatus::FAILED; }; diff --git a/nav2_util/CMakeLists.txt b/nav2_util/CMakeLists.txt index 164a90d0e449e6267f665792408677aff714b9db..782fb5e7fdacf3e67ce0803128291bc2fa665d8c 100644 --- a/nav2_util/CMakeLists.txt +++ b/nav2_util/CMakeLists.txt @@ -18,77 +18,7 @@ nav2_package() include_directories(include) set(library_name ${PROJECT_NAME}_core) -add_library(${library_name} SHARED - src/costmap.cpp - src/node_utils.cpp - src/lifecycle_service_client.cpp - src/string_utils.cpp - src/lifecycle_utils.cpp -) - -ament_target_dependencies(${library_name} - rclcpp - nav2_msgs - tf2 - tf2_ros - nav_msgs - geometry_msgs - lifecycle_msgs -) - -add_library(map_lib SHARED - src/map/map.c - src/map/map_store.c - src/map/map_range.c - src/map/map_draw.c - src/map/map_cspace.cpp -) - -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 -) - -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_link_libraries(sensors_lib pf_lib) - -add_library(motions_lib SHARED - src/motion_model/omni_motion_model.cpp - src/motion_model/differential_motion_model.cpp -) -target_link_libraries(motions_lib pf_lib) - -add_library(map_loader SHARED - src/map_loader/map_loader.cpp -) - -ament_target_dependencies(map_loader - geometry_msgs - tf2 - tf2_ros - nav_msgs - SDL - SDL_image -) - -target_link_libraries(map_loader - ${SDL_LIBRARY} - ${SDL_IMAGE_LIBRARIES} -) - -add_executable(lifecycle_bringup - src/lifecycle_bringup_commandline.cpp -) -target_link_libraries(lifecycle_bringup ${library_name}) +add_subdirectory(src) install(TARGETS ${library_name} diff --git a/nav2_util/src/CMakeLists.txt b/nav2_util/src/CMakeLists.txt new file mode 100644 index 0000000000000000000000000000000000000000..cd8d34e25415ce0baf0dc4dc02ee377f39807bad --- /dev/null +++ b/nav2_util/src/CMakeLists.txt @@ -0,0 +1,28 @@ +add_library(${library_name} SHARED + costmap.cpp + node_utils.cpp + lifecycle_service_client.cpp + string_utils.cpp + lifecycle_utils.cpp +) + +ament_target_dependencies(${library_name} + rclcpp + nav2_msgs + tf2 + tf2_ros + nav_msgs + geometry_msgs + lifecycle_msgs +) + +add_subdirectory(pf) +add_subdirectory(map) +add_subdirectory(map_loader) +add_subdirectory(motion_model) +add_subdirectory(sensors) + +add_executable(lifecycle_bringup + lifecycle_bringup_commandline.cpp +) +target_link_libraries(lifecycle_bringup ${library_name}) diff --git a/nav2_util/src/map/CMakeLists.txt b/nav2_util/src/map/CMakeLists.txt new file mode 100644 index 0000000000000000000000000000000000000000..357900c010aefd3ca560b9c10bfe6b63d9a89fca --- /dev/null +++ b/nav2_util/src/map/CMakeLists.txt @@ -0,0 +1,7 @@ +add_library(map_lib SHARED + map.c + map_store.c + map_range.c + map_draw.c + map_cspace.cpp +) diff --git a/nav2_util/src/map_loader/CMakeLists.txt b/nav2_util/src/map_loader/CMakeLists.txt new file mode 100644 index 0000000000000000000000000000000000000000..fe395cb5276bdcab56f1832eaeed123b669d02fa --- /dev/null +++ b/nav2_util/src/map_loader/CMakeLists.txt @@ -0,0 +1,17 @@ +add_library(map_loader SHARED + map_loader.cpp +) + +ament_target_dependencies(map_loader + geometry_msgs + tf2 + tf2_ros + nav_msgs + SDL + SDL_image +) + +target_link_libraries(map_loader + ${SDL_LIBRARY} + ${SDL_IMAGE_LIBRARIES} +) diff --git a/nav2_util/src/motion_model/CMakeLists.txt b/nav2_util/src/motion_model/CMakeLists.txt new file mode 100644 index 0000000000000000000000000000000000000000..1a14ea205daf5d72497b4d9e52a094b8afdccf9b --- /dev/null +++ b/nav2_util/src/motion_model/CMakeLists.txt @@ -0,0 +1,5 @@ +add_library(motions_lib SHARED + omni_motion_model.cpp + differential_motion_model.cpp +) +target_link_libraries(motions_lib pf_lib) diff --git a/nav2_util/src/pf/CMakeLists.txt b/nav2_util/src/pf/CMakeLists.txt new file mode 100644 index 0000000000000000000000000000000000000000..6b475ee066972553eb5094f6bd8bfe681c1b9730 --- /dev/null +++ b/nav2_util/src/pf/CMakeLists.txt @@ -0,0 +1,12 @@ +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 +) diff --git a/nav2_util/src/sensors/CMakeLists.txt b/nav2_util/src/sensors/CMakeLists.txt new file mode 100644 index 0000000000000000000000000000000000000000..34a2164d39405493793abc73c1b1d62826906893 --- /dev/null +++ b/nav2_util/src/sensors/CMakeLists.txt @@ -0,0 +1,7 @@ +add_library(sensors_lib SHARED + laser/laser.cpp + laser/beam_model.cpp + laser/likelihood_field_model.cpp + laser/likelihood_field_model_prob.cpp +) +target_link_libraries(sensors_lib pf_lib)