Skip to content
Snippets Groups Projects
Unverified Commit 90f12bc1 authored by Carl Delsey's avatar Carl Delsey Committed by GitHub
Browse files

Cleaning up warnings and errors detected by clang. (#658)

* Removing unused variables.

* Pass a floating point value to log print instead of Duration object.

* Another unused variable.

* Removing incorrect use of std::move.

* Fixing inheritance problems.

* Negation needed to be outside of parens. Order of operation error

* diagnostic state was never pushed.

* Disable folding constant warning in eig3.c file. It's used all over.

* Refactor nav2_util CMake structure to allow disabling warnings on just one directory.
parent 72b089b4
No related branches found
No related tags found
No related merge requests found
Showing
with 89 additions and 86 deletions
......@@ -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_;
......
......@@ -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_);
......
......@@ -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
......
......@@ -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_;
};
};
......
......@@ -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;
}
......
......@@ -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);
......
......@@ -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
......
......@@ -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;
......
......@@ -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
......
......@@ -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;
};
......
......@@ -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}
......
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})
add_library(map_lib SHARED
map.c
map_store.c
map_range.c
map_draw.c
map_cspace.cpp
)
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}
)
add_library(motions_lib SHARED
omni_motion_model.cpp
differential_motion_model.cpp
)
target_link_libraries(motions_lib pf_lib)
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
)
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)
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment