@@ -31,10 +31,8 @@ ClearEntireCostmapService::ClearEntireCostmapService(
3131void ClearEntireCostmapService::on_tick ()
3232{
3333 std::vector<std::string> plugins;
34- if (getInput (" plugins" , plugins)) {
35- request_->plugins = plugins;
36- } else {
37- request_->plugins = std::vector<std::string>();
34+ if (!getInput (" plugins" , request_->plugins )) {
35+ request_->plugins .clear ();
3836 }
3937 increment_recovery_count ();
4038}
@@ -71,10 +69,8 @@ void ClearCostmapAroundRobotService::on_tick()
7169 getInput (" reset_distance" , request_->reset_distance );
7270
7371 std::vector<std::string> plugins;
74- if (getInput (" plugins" , plugins)) {
75- request_->plugins = plugins;
76- } else {
77- request_->plugins = std::vector<std::string>();
72+ if (!getInput (" plugins" , request_->plugins )) {
73+ request_->plugins .clear ();
7874 }
7975
8076 increment_recovery_count ();
@@ -93,10 +89,8 @@ void ClearCostmapAroundPoseService::on_tick()
9389 getInput (" reset_distance" , request_->reset_distance );
9490
9591 std::vector<std::string> plugins;
96- if (getInput (" plugins" , plugins)) {
97- request_->plugins = plugins;
98- } else {
99- request_->plugins = std::vector<std::string>();
92+ if (!getInput (" plugins" , request_->plugins )) {
93+ request_->plugins .clear ();
10094 }
10195
10296 increment_recovery_count ();
0 commit comments