Skip to content

Commit 915925c

Browse files
fix typo and reset ports
Signed-off-by: BCKSELFDRIVEWORLD <[email protected]>
1 parent 8b38450 commit 915925c

File tree

3 files changed

+14
-2
lines changed

3 files changed

+14
-2
lines changed

nav2_behavior_tree/plugins/action/clear_costmap_service.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,8 @@ void ClearEntireCostmapService::on_tick()
3333
std::vector<std::string> plugins;
3434
if (getInput("plugins", plugins)) {
3535
request_->plugins = plugins;
36+
} else {
37+
request_->plugins = std::vector<std::string>();
3638
}
3739
increment_recovery_count();
3840
}
@@ -50,6 +52,8 @@ void ClearCostmapExceptRegionService::on_tick()
5052
std::vector<std::string> plugins;
5153
if (getInput("plugins", plugins)) {
5254
request_->plugins = plugins;
55+
} else {
56+
request_->plugins = std::vector<std::string>();
5357
}
5458

5559
increment_recovery_count();
@@ -69,6 +73,8 @@ void ClearCostmapAroundRobotService::on_tick()
6973
std::vector<std::string> plugins;
7074
if (getInput("plugins", plugins)) {
7175
request_->plugins = plugins;
76+
} else {
77+
request_->plugins = std::vector<std::string>();
7278
}
7379

7480
increment_recovery_count();
@@ -89,6 +95,8 @@ void ClearCostmapAroundPoseService::on_tick()
8995
std::vector<std::string> plugins;
9096
if (getInput("plugins", plugins)) {
9197
request_->plugins = plugins;
98+
} else {
99+
request_->plugins = std::vector<std::string>();
92100
}
93101

94102
increment_recovery_count();

nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,9 @@ class ClearCostmapService
6464
/**
6565
* @brief Clears the region around a specific pose
6666
*/
67-
void clearAroundPose(const geometry_msgs::msg::PoseStamped & pose, double reset_distance, const std::vector<std::string> & plugins);
67+
void clearAroundPose(
68+
const geometry_msgs::msg::PoseStamped & pose, double reset_distance,
69+
const std::vector<std::string> & plugins);
6870

6971
/**
7072
* @brief Clears all layers

nav2_costmap_2d/src/clear_costmap_service.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -155,7 +155,9 @@ void ClearCostmapService::clearAroundPose(
155155
}
156156
}
157157

158-
void ClearCostmapService::clearRegion(const double reset_distance, bool invert, const std::vector<std::string> & plugins)
158+
void ClearCostmapService::clearRegion(
159+
const double reset_distance, bool invert,
160+
const std::vector<std::string> & plugins)
159161
{
160162
double x, y;
161163

0 commit comments

Comments
 (0)