@@ -204,27 +204,23 @@ inline models::Path toTensor(const nav_msgs::msg::Path & path)
204204 * @brief Check if the robot pose is within the Goal Checker's tolerances to goal
205205 * @param global_checker Pointer to the goal checker
206206 * @param robot Pose of robot
207- * @param path Path to retrieve goal pose from
207+ * @param goal Goal pose
208208 * @return bool If robot is within goal checker tolerances to the goal
209209 */
210210inline bool withinPositionGoalTolerance (
211211 nav2_core::GoalChecker * goal_checker,
212212 const geometry_msgs::msg::Pose & robot,
213- const models::Path & path )
213+ const geometry_msgs::msg::Pose & goal )
214214{
215- const auto goal_idx = path.x .shape (0 ) - 1 ;
216- const auto goal_x = path.x (goal_idx);
217- const auto goal_y = path.y (goal_idx);
218-
219215 if (goal_checker) {
220216 geometry_msgs::msg::Pose pose_tolerance;
221217 geometry_msgs::msg::Twist velocity_tolerance;
222218 goal_checker->getTolerances (pose_tolerance, velocity_tolerance);
223219
224220 const auto pose_tolerance_sq = pose_tolerance.position .x * pose_tolerance.position .x ;
225221
226- auto dx = robot.position .x - goal_x ;
227- auto dy = robot.position .y - goal_y ;
222+ auto dx = robot.position .x - goal. position . x ;
223+ auto dy = robot.position .y - goal. position . y ;
228224
229225 auto dist_sq = dx * dx + dy * dy;
230226
@@ -240,25 +236,20 @@ inline bool withinPositionGoalTolerance(
240236 * @brief Check if the robot pose is within tolerance to the goal
241237 * @param pose_tolerance Pose tolerance to use
242238 * @param robot Pose of robot
243- * @param path Path to retrieve goal pose from
239+ * @param goal Goal pose
244240 * @return bool If robot is within tolerance to the goal
245241 */
246242inline bool withinPositionGoalTolerance (
247243 float pose_tolerance,
248244 const geometry_msgs::msg::Pose & robot,
249- const models::Path & path )
245+ const geometry_msgs::msg::Pose & goal )
250246{
251- const auto goal_idx = path. x . shape ( 0 ) - 1 ;
252- const float goal_x = path. x (goal_idx);
253- const float goal_y = path. y (goal_idx );
247+ const double & dist_sq =
248+ std::pow (goal. position . x - robot. position . x , 2 ) +
249+ std::pow (goal. position . y - robot. position . y , 2 );
254250
255251 const float pose_tolerance_sq = pose_tolerance * pose_tolerance;
256252
257- const float dx = static_cast <float >(robot.position .x ) - goal_x;
258- const float dy = static_cast <float >(robot.position .y ) - goal_y;
259-
260- float dist_sq = dx * dx + dy * dy;
261-
262253 if (dist_sq < pose_tolerance_sq) {
263254 return true ;
264255 }
0 commit comments