Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
34 commits
Select commit Hold shift + click to select a range
4a1c9e7
amcl: declare void parameter for functions with no args
srmainwaring Sep 21, 2023
15d0af1
amcl: remove unused variables
srmainwaring Sep 21, 2023
9585c05
behavior_tree: address clang compilation issues
srmainwaring Sep 21, 2023
159441d
behaviors: add missing override specifier
srmainwaring Sep 21, 2023
8b9e770
bt_navigator: add missing override specifier
srmainwaring Sep 21, 2023
32e5b99
collision_monitor: address clang compilation issues
srmainwaring Sep 21, 2023
12e86c2
collision_monitor: remove unused variables
srmainwaring Sep 22, 2023
fe36e8c
constrained_smoother: address clang compilation issues
srmainwaring Sep 21, 2023
921c813
controller: address clang compilation issues
srmainwaring Sep 21, 2023
186e552
costmap_2d: add missing override specifier
srmainwaring Sep 21, 2023
6c88f53
costmap_2d: address clang compilation issues
srmainwaring Sep 21, 2023
0a970c1
costmap_2d: fix link issue for order_layer
srmainwaring Sep 21, 2023
2cce5fb
dwb_controller: fix clang compile issue, replace ulong with uint32_t
srmainwaring Sep 21, 2023
34c8576
map_server: replace std::experimental::filesystem
srmainwaring Sep 21, 2023
f1c2a5f
map_server: remove dependency on stdc++fs
srmainwaring Sep 21, 2023
4d64a04
waypoint_follower: address clang compilation issues
srmainwaring Sep 21, 2023
9f1ef97
waypoint_follower: remove dependency on stdc++fs
srmainwaring Sep 21, 2023
fd26b67
waypoint_follower: replace std::experimental::filesystem
srmainwaring Sep 21, 2023
554ed32
smoother: address clang compilation issues
srmainwaring Sep 21, 2023
5ba61c3
smoother: remove unused variables
srmainwaring Sep 21, 2023
71cbc3a
system_tests: remove dependency on stdc++fs
srmainwaring Sep 21, 2023
22da9c3
rotation_shim_controller: update percentage arg in setSpeedLimit to b…
srmainwaring Sep 21, 2023
897e2e0
planner: remove unused variables
srmainwaring Sep 21, 2023
e81c6a6
costmap_2d: address clang compilation issues
srmainwaring Sep 21, 2023
8eeb47c
mppi_controller: replace use of auto as function param with templates
srmainwaring Sep 21, 2023
c3e485b
mppi_controller: address clang compilation issues
srmainwaring Sep 21, 2023
1ec29db
costmap_2d: resolve clang issue with std::pair non-const copy
srmainwaring Sep 21, 2023
f5c479f
smac_planner: suppress unused parameter warnings
srmainwaring Sep 22, 2023
16dabba
behavior_tree: fix code style
srmainwaring Sep 27, 2023
3df21f7
costmap_2d: fix code style
srmainwaring Sep 27, 2023
d7a107e
mppi_controller: revert reindexing of for-loop
srmainwaring Sep 28, 2023
5821f39
smoother: remove commented code
srmainwaring Sep 28, 2023
6adaf53
system_tests: remove commented target link library
srmainwaring Sep 28, 2023
8ac6406
collision_monitor: revert parameter type to vector and use explicit c…
srmainwaring Sep 28, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions nav2_amcl/include/nav2_amcl/pf/pf_vector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ typedef struct


// Return a zero vector
pf_vector_t pf_vector_zero();
pf_vector_t pf_vector_zero(void);

// Check for NAN or INF in any component
// int pf_vector_finite(pf_vector_t a);
Expand All @@ -71,7 +71,7 @@ pf_vector_t pf_vector_coord_add(pf_vector_t a, pf_vector_t b);


// Return a zero matrix
pf_matrix_t pf_matrix_zero();
pf_matrix_t pf_matrix_zero(void);

// Check for NAN or INF in any component
// int pf_matrix_finite(pf_matrix_t a);
Expand Down
5 changes: 0 additions & 5 deletions nav2_amcl/src/pf/pf.c
Original file line number Diff line number Diff line change
Expand Up @@ -463,7 +463,6 @@ void pf_cluster_stats(pf_t * pf, pf_sample_set_t * set)

// Workspace
double m[4], c[2][2];
size_t count;
double weight;

// Cluster the samples
Expand All @@ -474,7 +473,6 @@ void pf_cluster_stats(pf_t * pf, pf_sample_set_t * set)

for (i = 0; i < set->cluster_max_count; i++) {
cluster = set->clusters + i;
cluster->count = 0;
cluster->weight = 0;
cluster->mean = pf_vector_zero();
cluster->cov = pf_matrix_zero();
Expand All @@ -490,7 +488,6 @@ void pf_cluster_stats(pf_t * pf, pf_sample_set_t * set)
}

// Initialize overall filter stats
count = 0;
weight = 0.0;
set->mean = pf_vector_zero();
set->cov = pf_matrix_zero();
Expand Down Expand Up @@ -521,10 +518,8 @@ void pf_cluster_stats(pf_t * pf, pf_sample_set_t * set)

cluster = set->clusters + cidx;

cluster->count += 1;
cluster->weight += sample->weight;

count += 1;
weight += sample->weight;

// Compute mean
Expand Down
4 changes: 2 additions & 2 deletions nav2_amcl/src/pf/pf_vector.c
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@


// Return a zero vector
pf_vector_t pf_vector_zero()
pf_vector_t pf_vector_zero(void)
{
pf_vector_t c;

Expand Down Expand Up @@ -130,7 +130,7 @@ pf_vector_t pf_vector_coord_add(pf_vector_t a, pf_vector_t b)


// Return a zero matrix
pf_matrix_t pf_matrix_zero()
pf_matrix_t pf_matrix_zero(void)
{
int i, j;
pf_matrix_t c;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,8 @@ class BtActionNode : public BT::ActionNodeBase
// if new goal was sent and action server has not yet responded
// check the future goal handle
if (future_goal_handle_) {
auto elapsed = (node_->now() - time_goal_sent_).to_chrono<std::chrono::milliseconds>();
auto elapsed =
(node_->now() - time_goal_sent_).template to_chrono<std::chrono::milliseconds>();
if (!is_future_goal_handle_complete(elapsed)) {
// return RUNNING if there is still some time before timeout happens
if (elapsed < server_timeout_) {
Expand Down Expand Up @@ -237,7 +238,8 @@ class BtActionNode : public BT::ActionNodeBase
{
goal_updated_ = false;
send_new_goal();
auto elapsed = (node_->now() - time_goal_sent_).to_chrono<std::chrono::milliseconds>();
auto elapsed =
(node_->now() - time_goal_sent_).template to_chrono<std::chrono::milliseconds>();
if (!is_future_goal_handle_complete(elapsed)) {
if (elapsed < server_timeout_) {
return BT::NodeStatus::RUNNING;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ class BtCancelActionNode : public BT::ActionNodeBase
return basic;
}

void halt()
void halt() override
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ class BtServiceNode : public BT::ActionNodeBase
*/
virtual BT::NodeStatus check_future()
{
auto elapsed = (node_->now() - sent_time_).to_chrono<std::chrono::milliseconds>();
auto elapsed = (node_->now() - sent_time_).template to_chrono<std::chrono::milliseconds>();
auto remaining = server_timeout_ - elapsed;

if (remaining > std::chrono::milliseconds(0)) {
Expand All @@ -199,7 +199,7 @@ class BtServiceNode : public BT::ActionNodeBase

if (rc == rclcpp::FutureReturnCode::TIMEOUT) {
on_wait_for_result();
elapsed = (node_->now() - sent_time_).to_chrono<std::chrono::milliseconds>();
elapsed = (node_->now() - sent_time_).template to_chrono<std::chrono::milliseconds>();
if (elapsed < server_timeout_) {
return BT::NodeStatus::RUNNING;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ void IsStuckCondition::logStuck(const std::string & msg) const
return;
}

RCLCPP_INFO(node_->get_logger(), msg.c_str());
RCLCPP_INFO(node_->get_logger(), "%s", msg.c_str());
prev_msg = msg;
}

Expand Down
2 changes: 1 addition & 1 deletion nav2_behavior_tree/plugins/decorator/speed_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ SpeedController::SpeedController(

if (min_rate_ <= 0.0 || max_rate_ <= 0.0) {
std::string err_msg = "SpeedController node cannot have rate <= 0.0";
RCLCPP_FATAL(node_->get_logger(), err_msg.c_str());
RCLCPP_FATAL(node_->get_logger(), "%s", err_msg.c_str());
throw BT::BehaviorTreeException(err_msg);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ class DriveOnHeading : public TimedBehavior<ActionT>
* @brief Loop function to run behavior
* @return Status of behavior
*/
ResultStatus onCycleUpdate()
ResultStatus onCycleUpdate() override
{
rclcpp::Duration time_remaining = end_time_ - this->steady_clock_.now();
if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ class NavigateToPoseNavigator
* @brief Get action name for this navigator
* @return string Name of action server
*/
std::string getName() {return std::string("navigate_to_pose");}
std::string getName() override {return std::string("navigate_to_pose");}

/**
* @brief Get navigator's default BT
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ static constexpr double EPSILON = 1e-5;
static const char BASE_FRAME_ID[]{"base_link"};
static const char SOURCE_FRAME_ID[]{"base_source"};
static const char ODOM_FRAME_ID[]{"odom"};
static const char FOOTPRINT_TOPIC[]{"footprint"};
static const char SCAN_NAME[]{"Scan"};
static const char POINTCLOUD_NAME[]{"PointCloud"};
static const char RANGE_NAME[]{"Range"};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1022,7 +1022,7 @@ TEST_F(Tester, testSourcesNotSet)
setCommonParameters();
addPolygon("Stop", POLYGON, 1.0, "stop");
addSource(SCAN_NAME, SCAN);
cm_->declare_parameter("polygons", rclcpp::ParameterValue({"Stop"}));
cm_->declare_parameter("polygons", rclcpp::ParameterValue(std::vector<std::string>{"Stop"}));
cm_->set_parameter(rclcpp::Parameter("polygons", std::vector<std::string>{"Stop"}));

// Check that Collision Monitor node can not be configured for this parameters set
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ class SmootherTest : public ::testing::Test
SmootherTest() {SetUp();}
~SmootherTest() {}

void SetUp()
void SetUp() override
{
node_lifecycle_ =
std::make_shared<rclcpp_lifecycle::LifecycleNode>(
Expand Down
2 changes: 1 addition & 1 deletion nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -594,7 +594,7 @@ void ControllerServer::computeAndPublishVelocity()
// other types will not be resolved with more attempts
} catch (nav2_core::NoValidControl & e) {
if (failure_tolerance_ > 0 || failure_tolerance_ == -1.0) {
RCLCPP_WARN(this->get_logger(), e.what());
RCLCPP_WARN(this->get_logger(), "%s", e.what());
cmd_vel_2d.twist.angular.x = 0;
cmd_vel_2d.twist.angular.y = 0;
cmd_vel_2d.twist.angular.z = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -986,9 +986,10 @@ class GroupsRemover
const IsBg & is_background) const
{
// Creates an image labels in which each obstacles group is labeled with a unique code
auto components = connectedComponents<connectivity>(image, buffer, label_trees, is_background);
const Label groups_count = components.second;
const Image<Label> & labels = components.first;
Label groups_count;
auto labels = connectedComponents<connectivity>(
image, buffer, label_trees,
is_background, groups_count);

// Calculates the size of each group.
// Group size is equal to the number of pixels with the same label
Expand Down Expand Up @@ -1029,24 +1030,27 @@ class GroupsRemover
} // namespace imgproc_impl

template<ConnectivityType connectivity, class Label, class IsBg>
std::pair<Image<Label>, Label> connectedComponents(
Image<Label> connectedComponents(
const Image<uint8_t> & image, MemoryBuffer & buffer,
imgproc_impl::EquivalenceLabelTrees<Label> & label_trees, const IsBg & is_background)
imgproc_impl::EquivalenceLabelTrees<Label> & label_trees,
const IsBg & is_background,
Label & total_labels)
{
using namespace imgproc_impl;
const size_t pixels = image.rows() * image.columns();

if (pixels == 0) {
return {Image<Label>{}, 0};
total_labels = 0;
return Image<Label>{};
}

Label * image_buffer = buffer.get<Label>(pixels);
Image<Label> labels(image.rows(), image.columns(), image_buffer, image.columns());
label_trees.reset(image.rows(), image.columns(), connectivity);
const Label total_labels = connectedComponentsImpl<connectivity>(
total_labels = connectedComponentsImpl<connectivity>(
image, labels, label_trees,
is_background);
return std::make_pair(labels, total_labels);
return labels;
}

} // namespace nav2_costmap_2d
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ class InflationLayer : public Layer
/**
* @brief If clearing operations should be processed on this layer or not
*/
virtual bool isClearable() {return false;}
virtual bool isClearable() override {return false;}

/**
* @brief Reset this costmap
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/plugins/denoise_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ DenoiseLayer::updateCosts(
try {
denoise(roi_image);
} catch (std::exception & ex) {
RCLCPP_ERROR(logger_, (std::string("Inner error: ") + ex.what()).c_str());
RCLCPP_ERROR(logger_, "%s", (std::string("Inner error: ") + ex.what()).c_str());
}

current_ = true;
Expand Down
6 changes: 3 additions & 3 deletions nav2_costmap_2d/src/clear_costmap_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ void ClearCostmapService::clearExceptRegionCallback(
const shared_ptr<ClearExceptRegion::Response>/*response*/)
{
RCLCPP_INFO(
logger_,
logger_, "%s",
("Received request to clear except a region the " + costmap_.getName()).c_str());

clearRegion(request->reset_distance, true);
Expand All @@ -87,7 +87,7 @@ void ClearCostmapService::clearEntireCallback(
const std::shared_ptr<ClearEntirely::Response>/*response*/)
{
RCLCPP_INFO(
logger_,
logger_, "%s",
("Received request to clear entirely the " + costmap_.getName()).c_str());

clearEntirely();
Expand All @@ -99,7 +99,7 @@ void ClearCostmapService::clearRegion(const double reset_distance, bool invert)

if (!getPosition(x, y)) {
RCLCPP_ERROR(
logger_,
logger_, "%s",
"Cannot clear map because robot pose cannot be retrieved.");
return;
}
Expand Down
3 changes: 3 additions & 0 deletions nav2_costmap_2d/test/regression/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,9 @@ add_library(order_layer SHARED
ament_target_dependencies(order_layer
${dependencies}
)
target_link_libraries(order_layer
nav2_costmap_2d_core
)
install(TARGETS
order_layer
ARCHIVE DESTINATION lib
Expand Down
6 changes: 3 additions & 3 deletions nav2_costmap_2d/test/unit/denoise_layer_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -407,9 +407,9 @@ TEST_F(DenoiseLayerTester, denoiseNothing) {

TEST_F(DenoiseLayerTester, constructorAndDestructor) {
ASSERT_NO_THROW(
[]() {
nav2_costmap_2d::DenoiseLayer layer;
});
{
nav2_costmap_2d::DenoiseLayer layer;
});
}

TEST_F(DenoiseLayerTester, reset) {
Expand Down
Loading