Skip to content

Commit 54a45cb

Browse files
authored
Fixes for compiling with clang on macOS (#4051)
amcl: declare void parameter for functions with no args amcl: remove unused variables behavior_tree: address clang compilation issues behaviors: add missing override specifier bt_navigator: add missing override specifier collision_monitor: address clang compilation issues constrained_smoother: address clang compilation issues controller: address clang compilation issues costmap_2d: add missing override specifier costmap_2d: address clang compilation issues costmap_2d: fix link issue for order_layer dwb_controller: fix clang compile issue, replace ulong with uint32_t map_server: replace std::experimental::filesystem map_server: remove dependency on stdc++fs waypoint_follower: address clang compilation issues waypoint_follower: remove dependency on stdc++fs waypoint_follower: replace std::experimental::filesystem smoother: address clang compilation issues smoother: remove unused variables system_tests: remove dependency on stdc++fs rotation_shim_controller: update percentage arg in setSpeedLimit to boolean planner: remove unused variables costmap_2d: address clang compilation issues mppi_controller: replace use of auto as function param with templates mppi_controller: address clang compilation issues costmap_2d: resolve clang issue with std::pair non-const copy Signed-off-by: Rhys Mainwaring <[email protected]>
1 parent abe4149 commit 54a45cb

File tree

43 files changed

+149
-131
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

43 files changed

+149
-131
lines changed

nav2_amcl/include/nav2_amcl/pf/pf_vector.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ typedef struct
4949

5050

5151
// Return a zero vector
52-
pf_vector_t pf_vector_zero();
52+
pf_vector_t pf_vector_zero(void);
5353

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

7272

7373
// Return a zero matrix
74-
pf_matrix_t pf_matrix_zero();
74+
pf_matrix_t pf_matrix_zero(void);
7575

7676
// Check for NAN or INF in any component
7777
// int pf_matrix_finite(pf_matrix_t a);

nav2_amcl/src/pf/pf.c

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -463,7 +463,6 @@ void pf_cluster_stats(pf_t * pf, pf_sample_set_t * set)
463463

464464
// Workspace
465465
double m[4], c[2][2];
466-
size_t count;
467466
double weight;
468467

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

475474
for (i = 0; i < set->cluster_max_count; i++) {
476475
cluster = set->clusters + i;
477-
cluster->count = 0;
478476
cluster->weight = 0;
479477
cluster->mean = pf_vector_zero();
480478
cluster->cov = pf_matrix_zero();
@@ -490,7 +488,6 @@ void pf_cluster_stats(pf_t * pf, pf_sample_set_t * set)
490488
}
491489

492490
// Initialize overall filter stats
493-
count = 0;
494491
weight = 0.0;
495492
set->mean = pf_vector_zero();
496493
set->cov = pf_matrix_zero();
@@ -521,10 +518,8 @@ void pf_cluster_stats(pf_t * pf, pf_sample_set_t * set)
521518

522519
cluster = set->clusters + cidx;
523520

524-
cluster->count += 1;
525521
cluster->weight += sample->weight;
526522

527-
count += 1;
528523
weight += sample->weight;
529524

530525
// Compute mean

nav2_amcl/src/pf/pf_vector.c

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@
3535

3636

3737
// Return a zero vector
38-
pf_vector_t pf_vector_zero()
38+
pf_vector_t pf_vector_zero(void)
3939
{
4040
pf_vector_t c;
4141

@@ -130,7 +130,7 @@ pf_vector_t pf_vector_coord_add(pf_vector_t a, pf_vector_t b)
130130

131131

132132
// Return a zero matrix
133-
pf_matrix_t pf_matrix_zero()
133+
pf_matrix_t pf_matrix_zero(void)
134134
{
135135
int i, j;
136136
pf_matrix_t c;

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -206,7 +206,7 @@ class BtActionNode : public BT::ActionNodeBase
206206
// if new goal was sent and action server has not yet responded
207207
// check the future goal handle
208208
if (future_goal_handle_) {
209-
auto elapsed = (node_->now() - time_goal_sent_).to_chrono<std::chrono::milliseconds>();
209+
auto elapsed = (node_->now() - time_goal_sent_).template to_chrono<std::chrono::milliseconds>();
210210
if (!is_future_goal_handle_complete(elapsed)) {
211211
// return RUNNING if there is still some time before timeout happens
212212
if (elapsed < server_timeout_) {
@@ -236,7 +236,7 @@ class BtActionNode : public BT::ActionNodeBase
236236
{
237237
goal_updated_ = false;
238238
send_new_goal();
239-
auto elapsed = (node_->now() - time_goal_sent_).to_chrono<std::chrono::milliseconds>();
239+
auto elapsed = (node_->now() - time_goal_sent_).template to_chrono<std::chrono::milliseconds>();
240240
if (!is_future_goal_handle_complete(elapsed)) {
241241
if (elapsed < server_timeout_) {
242242
return BT::NodeStatus::RUNNING;

nav2_behavior_tree/include/nav2_behavior_tree/bt_cancel_action_node.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -116,7 +116,7 @@ class BtCancelActionNode : public BT::ActionNodeBase
116116
return basic;
117117
}
118118

119-
void halt()
119+
void halt() override
120120
{
121121
}
122122

nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -183,7 +183,7 @@ class BtServiceNode : public BT::ActionNodeBase
183183
*/
184184
virtual BT::NodeStatus check_future()
185185
{
186-
auto elapsed = (node_->now() - sent_time_).to_chrono<std::chrono::milliseconds>();
186+
auto elapsed = (node_->now() - sent_time_).template to_chrono<std::chrono::milliseconds>();
187187
auto remaining = server_timeout_ - elapsed;
188188

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

200200
if (rc == rclcpp::FutureReturnCode::TIMEOUT) {
201201
on_wait_for_result();
202-
elapsed = (node_->now() - sent_time_).to_chrono<std::chrono::milliseconds>();
202+
elapsed = (node_->now() - sent_time_).template to_chrono<std::chrono::milliseconds>();
203203
if (elapsed < server_timeout_) {
204204
return BT::NodeStatus::RUNNING;
205205
}

nav2_behavior_tree/plugins/condition/is_stuck_condition.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -95,7 +95,7 @@ void IsStuckCondition::logStuck(const std::string & msg) const
9595
return;
9696
}
9797

98-
RCLCPP_INFO(node_->get_logger(), msg.c_str());
98+
RCLCPP_INFO(node_->get_logger(), "%s", msg.c_str());
9999
prev_msg = msg;
100100
}
101101

nav2_behavior_tree/plugins/decorator/speed_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ SpeedController::SpeedController(
4343

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

nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,7 @@ class DriveOnHeading : public TimedBehavior<ActionT>
9191
* @brief Loop function to run behavior
9292
* @return Status of behavior
9393
*/
94-
Status onCycleUpdate()
94+
Status onCycleUpdate() override
9595
{
9696
rclcpp::Duration time_remaining = end_time_ - this->steady_clock_.now();
9797
if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {

nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_to_pose.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ class NavigateToPoseNavigator
7272
* @brief Get action name for this navigator
7373
* @return string Name of action server
7474
*/
75-
std::string getName() {return std::string("navigate_to_pose");}
75+
std::string getName() override {return std::string("navigate_to_pose");}
7676

7777
/**
7878
* @brief Get navigator's default BT

0 commit comments

Comments
 (0)