Skip to content

Commit e48b01a

Browse files
committed
Update regulated_pure_pursuit_controller.cpp (#2484)
1 parent 0e47041 commit e48b01a

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ void RegulatedPurePursuitController::configure(
4343
{
4444
auto node = parent.lock();
4545
if (!node) {
46-
throw std::runtime_error("Unable to lock node!");
46+
throw nav2_core::PlannerException("Unable to lock node!");
4747
}
4848

4949
costmap_ros_ = costmap_ros;
@@ -314,7 +314,7 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
314314

315315
// Collision checking on this velocity heading
316316
if (isCollisionImminent(pose, linear_vel, angular_vel)) {
317-
throw std::runtime_error("RegulatedPurePursuitController detected collision ahead!");
317+
throw nav2_core::PlannerException("RegulatedPurePursuitController detected collision ahead!");
318318
}
319319

320320
// populate and return message

0 commit comments

Comments
 (0)