Skip to content

Commit

Permalink
Fix/controller exception (#23)
Browse files Browse the repository at this point in the history
* fix for acceleration limits (#17)

* on par with the controller server
  • Loading branch information
padhupradheep authored Nov 9, 2022
1 parent 2035608 commit 5037c0f
Showing 1 changed file with 6 additions and 6 deletions.
12 changes: 6 additions & 6 deletions src/NeoMpcPlanner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ SOFTWARE.
#include <vector>
#include "nav2_util/line_iterator.hpp"
#include "nav2_core/goal_checker.hpp"
#include "nav2_core/exceptions.hpp"
#include "nav2_core/controller_exceptions.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
Expand Down Expand Up @@ -67,13 +67,13 @@ nav_msgs::msg::Path NeoMpcPlanner::transformGlobalPlan(
const geometry_msgs::msg::PoseStamped & pose)
{
if (global_plan_.poses.empty()) {
throw nav2_core::PlannerException("Received plan with zero length");
throw nav2_core::ControllerException("Received plan with zero length");
}

// let's get the pose of the robot in the frame of the plan
geometry_msgs::msg::PoseStamped robot_pose;
if (!transformPose(global_plan_.header.frame_id, pose, robot_pose)) {
throw nav2_core::PlannerException("Unable to transform robot pose into global plan's frame");
throw nav2_core::ControllerException("Unable to transform robot pose into global plan's frame");
}

// We'll discard points on the plan that are outside the local costmap
Expand Down Expand Up @@ -128,7 +128,7 @@ nav_msgs::msg::Path NeoMpcPlanner::transformGlobalPlan(
global_path_pub_->publish(transformed_plan);

if (transformed_plan.poses.empty()) {
throw nav2_core::PlannerException("Resulting plan has 0 poses in it.");
throw nav2_core::ControllerException("Resulting plan has 0 poses in it.");
}

return transformed_plan;
Expand Down Expand Up @@ -231,7 +231,7 @@ geometry_msgs::msg::TwistStamped NeoMpcPlanner::computeVelocityCommands(
}

if (footprint_cost == 255) {
throw nav2_core::PlannerException("MPC detected collision!");
throw nav2_core::ControllerException("MPC detected collision!");
}

carrot_pub_->publish(createCarrotMsg(carrot_pose));
Expand Down Expand Up @@ -288,7 +288,7 @@ void NeoMpcPlanner::configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr & p
auto node = parent.lock();
node_ = parent;
if (!node) {
throw nav2_core::PlannerException("Unable to lock node!");
throw nav2_core::ControllerException("Unable to lock node!");
}

costmap_ros_ = costmap_ros;
Expand Down

0 comments on commit 5037c0f

Please sign in to comment.