@@ -51,7 +51,8 @@ class UnknownErrorPlanner : public nav2_core::GlobalPlanner
5151
5252 nav_msgs::msg::Path createPlan (
5353 const geometry_msgs::msg::PoseStamped &,
54- const geometry_msgs::msg::PoseStamped &) override
54+ const geometry_msgs::msg::PoseStamped &,
55+ std::function<bool ()>) override
5556 {
5657 throw nav2_core::PlannerException (" Unknown Error" );
5758 }
@@ -61,7 +62,8 @@ class StartOccupiedErrorPlanner : public UnknownErrorPlanner
6162{
6263 nav_msgs::msg::Path createPlan (
6364 const geometry_msgs::msg::PoseStamped &,
64- const geometry_msgs::msg::PoseStamped &) override
65+ const geometry_msgs::msg::PoseStamped &,
66+ std::function<bool ()>) override
6567 {
6668 throw nav2_core::StartOccupied (" Start Occupied" );
6769 }
@@ -71,7 +73,8 @@ class GoalOccupiedErrorPlanner : public UnknownErrorPlanner
7173{
7274 nav_msgs::msg::Path createPlan (
7375 const geometry_msgs::msg::PoseStamped &,
74- const geometry_msgs::msg::PoseStamped &) override
76+ const geometry_msgs::msg::PoseStamped &,
77+ std::function<bool ()>) override
7578 {
7679 throw nav2_core::GoalOccupied (" Goal occupied" );
7780 }
@@ -81,7 +84,8 @@ class StartOutsideMapErrorPlanner : public UnknownErrorPlanner
8184{
8285 nav_msgs::msg::Path createPlan (
8386 const geometry_msgs::msg::PoseStamped &,
84- const geometry_msgs::msg::PoseStamped &) override
87+ const geometry_msgs::msg::PoseStamped &,
88+ std::function<bool ()>) override
8589 {
8690 throw nav2_core::StartOutsideMapBounds (" Start OutsideMapBounds" );
8791 }
@@ -91,7 +95,8 @@ class GoalOutsideMapErrorPlanner : public UnknownErrorPlanner
9195{
9296 nav_msgs::msg::Path createPlan (
9397 const geometry_msgs::msg::PoseStamped &,
94- const geometry_msgs::msg::PoseStamped &) override
98+ const geometry_msgs::msg::PoseStamped &,
99+ std::function<bool ()>) override
95100 {
96101 throw nav2_core::GoalOutsideMapBounds (" Goal outside map bounds" );
97102 }
@@ -101,7 +106,8 @@ class NoValidPathErrorPlanner : public UnknownErrorPlanner
101106{
102107 nav_msgs::msg::Path createPlan (
103108 const geometry_msgs::msg::PoseStamped &,
104- const geometry_msgs::msg::PoseStamped &) override
109+ const geometry_msgs::msg::PoseStamped &,
110+ std::function<bool ()>) override
105111 {
106112 return nav_msgs::msg::Path ();
107113 }
@@ -112,7 +118,8 @@ class TimedOutErrorPlanner : public UnknownErrorPlanner
112118{
113119 nav_msgs::msg::Path createPlan (
114120 const geometry_msgs::msg::PoseStamped &,
115- const geometry_msgs::msg::PoseStamped &) override
121+ const geometry_msgs::msg::PoseStamped &,
122+ std::function<bool ()>) override
116123 {
117124 throw nav2_core::PlannerTimedOut (" Planner Timed Out" );
118125 }
@@ -122,7 +129,8 @@ class TFErrorPlanner : public UnknownErrorPlanner
122129{
123130 nav_msgs::msg::Path createPlan (
124131 const geometry_msgs::msg::PoseStamped &,
125- const geometry_msgs::msg::PoseStamped &) override
132+ const geometry_msgs::msg::PoseStamped &,
133+ std::function<bool ()>) override
126134 {
127135 throw nav2_core::PlannerTFError (" TF Error" );
128136 }
@@ -132,7 +140,8 @@ class NoViapointsGivenErrorPlanner : public UnknownErrorPlanner
132140{
133141 nav_msgs::msg::Path createPlan (
134142 const geometry_msgs::msg::PoseStamped &,
135- const geometry_msgs::msg::PoseStamped &) override
143+ const geometry_msgs::msg::PoseStamped &,
144+ std::function<bool ()>) override
136145 {
137146 throw nav2_core::NoViapointsGiven (" No Via points given" );
138147 }
0 commit comments