@@ -181,6 +181,139 @@ TEST_F(RemoveInCollisionGoalsTestFixture, test_tick_remove_in_collision_goals_su
181181 EXPECT_EQ (output_poses.goals [2 ], poses.goals [2 ]);
182182}
183183
184+ TEST_F (RemoveInCollisionGoalsTestFixture,
185+ test_tick_remove_in_collision_goals_success_and_output_waypoint_statues)
186+ {
187+ // create tree
188+ std::string xml_txt =
189+ R"(
190+ <root BTCPP_format="4">
191+ <BehaviorTree ID="MainTree">
192+ <RemoveInCollisionGoals service_name="/global_costmap/get_cost_global_costmap"
193+ input_goals="{goals}" output_goals="{goals}"
194+ cost_threshold="253"
195+ input_waypoint_statuses="{waypoint_statuses}"
196+ output_waypoint_statuses="{waypoint_statuses}"/>
197+ </BehaviorTree>
198+ </root>)" ;
199+
200+ tree_ = std::make_shared<BT::Tree>(factory_->createTreeFromText (xml_txt, config_->blackboard ));
201+
202+ // create new goal and set it on blackboard
203+ nav_msgs::msg::Goals poses;
204+ poses.goals .resize (4 );
205+ poses.goals [0 ].pose .position .x = 0.0 ;
206+ poses.goals [0 ].pose .position .y = 0.0 ;
207+
208+ poses.goals [1 ].pose .position .x = 0.5 ;
209+ poses.goals [1 ].pose .position .y = 0.0 ;
210+
211+ poses.goals [2 ].pose .position .x = 1.0 ;
212+ poses.goals [2 ].pose .position .y = 0.0 ;
213+
214+ poses.goals [3 ].pose .position .x = 2.0 ;
215+ poses.goals [3 ].pose .position .y = 0.0 ;
216+
217+ config_->blackboard ->set (" goals" , poses);
218+
219+ // create waypoint_statuses and set it on blackboard
220+ std::vector<nav2_msgs::msg::WaypointStatus> waypoint_statuses (poses.goals .size ());
221+ for (size_t i = 0 ; i < waypoint_statuses.size () ; ++i) {
222+ waypoint_statuses[i].waypoint_pose = poses.goals [i];
223+ waypoint_statuses[i].waypoint_index = i;
224+ }
225+ config_->blackboard ->set (" waypoint_statuses" , waypoint_statuses);
226+
227+ // tick until node is not running
228+ tree_->rootNode ()->executeTick ();
229+ while (tree_->rootNode ()->status () == BT::NodeStatus::RUNNING) {
230+ tree_->rootNode ()->executeTick ();
231+ }
232+
233+ EXPECT_EQ (tree_->rootNode ()->status (), BT::NodeStatus::SUCCESS);
234+ // check that it removed the point in range
235+ nav_msgs::msg::Goals output_poses;
236+ EXPECT_TRUE (config_->blackboard ->get (" goals" , output_poses));
237+
238+ EXPECT_EQ (output_poses.goals .size (), 3u );
239+ EXPECT_EQ (output_poses.goals [0 ], poses.goals [0 ]);
240+ EXPECT_EQ (output_poses.goals [1 ], poses.goals [1 ]);
241+ EXPECT_EQ (output_poses.goals [2 ], poses.goals [2 ]);
242+
243+ // check the waypoint_statuses
244+ std::vector<nav2_msgs::msg::WaypointStatus> output_waypoint_statuses;
245+ EXPECT_TRUE (config_->blackboard ->get (" waypoint_statuses" , output_waypoint_statuses));
246+ EXPECT_EQ (output_waypoint_statuses.size (), 4u );
247+ EXPECT_EQ (output_waypoint_statuses[0 ].waypoint_status , nav2_msgs::msg::WaypointStatus::PENDING);
248+ EXPECT_EQ (output_waypoint_statuses[1 ].waypoint_status , nav2_msgs::msg::WaypointStatus::PENDING);
249+ EXPECT_EQ (output_waypoint_statuses[2 ].waypoint_status , nav2_msgs::msg::WaypointStatus::PENDING);
250+ EXPECT_EQ (output_waypoint_statuses[3 ].waypoint_status , nav2_msgs::msg::WaypointStatus::SKIPPED);
251+ }
252+
253+ TEST_F (RemoveInCollisionGoalsTestFixture,
254+ test_tick_remove_in_collision_goals_find_matching_waypoint_fail)
255+ {
256+ // create tree
257+ std::string xml_txt =
258+ R"(
259+ <root BTCPP_format="4">
260+ <BehaviorTree ID="MainTree">
261+ <RemoveInCollisionGoals service_name="/global_costmap/get_cost_global_costmap"
262+ input_goals="{goals}" output_goals="{goals}"
263+ cost_threshold="253"
264+ input_waypoint_statuses="{waypoint_statuses}"
265+ output_waypoint_statuses="{waypoint_statuses}"/>
266+ </BehaviorTree>
267+ </root>)" ;
268+
269+ tree_ = std::make_shared<BT::Tree>(factory_->createTreeFromText (xml_txt, config_->blackboard ));
270+
271+ // create new goal and set it on blackboard
272+ nav_msgs::msg::Goals poses;
273+ poses.goals .resize (4 );
274+ poses.goals [0 ].pose .position .x = 0.0 ;
275+ poses.goals [0 ].pose .position .y = 0.0 ;
276+
277+ poses.goals [1 ].pose .position .x = 0.5 ;
278+ poses.goals [1 ].pose .position .y = 0.0 ;
279+
280+ poses.goals [2 ].pose .position .x = 1.0 ;
281+ poses.goals [2 ].pose .position .y = 0.0 ;
282+
283+ poses.goals [3 ].pose .position .x = 2.0 ;
284+ poses.goals [3 ].pose .position .y = 0.0 ;
285+
286+ config_->blackboard ->set (" goals" , poses);
287+
288+ // create waypoint_statuses and set it on blackboard
289+ std::vector<nav2_msgs::msg::WaypointStatus> waypoint_statuses (poses.goals .size ());
290+ for (size_t i = 0 ; i < waypoint_statuses.size () ; ++i) {
291+ waypoint_statuses[i].waypoint_pose = poses.goals [i];
292+ waypoint_statuses[i].waypoint_index = i;
293+ }
294+ // inconsistency between waypoint_statuses and poses
295+ waypoint_statuses[3 ].waypoint_pose .pose .position .x = 0.0 ;
296+
297+ config_->blackboard ->set (" waypoint_statuses" , waypoint_statuses);
298+
299+ // tick until node is not running
300+ tree_->rootNode ()->executeTick ();
301+ while (tree_->rootNode ()->status () == BT::NodeStatus::RUNNING) {
302+ tree_->rootNode ()->executeTick ();
303+ }
304+
305+ // check that it failed and returned the original goals
306+ EXPECT_EQ (tree_->rootNode ()->status (), BT::NodeStatus::FAILURE);
307+ nav_msgs::msg::Goals output_poses;
308+ EXPECT_TRUE (config_->blackboard ->get (" goals" , output_poses));
309+
310+ EXPECT_EQ (output_poses.goals .size (), 4u );
311+ EXPECT_EQ (output_poses.goals [0 ], poses.goals [0 ]);
312+ EXPECT_EQ (output_poses.goals [1 ], poses.goals [1 ]);
313+ EXPECT_EQ (output_poses.goals [2 ], poses.goals [2 ]);
314+ EXPECT_EQ (output_poses.goals [3 ], poses.goals [3 ]);
315+ }
316+
184317TEST_F (RemoveInCollisionGoalsTestFixture, test_tick_remove_in_collision_goals_fail)
185318{
186319 // create tree
0 commit comments