Skip to content

Commit

Permalink
Rename init() to initialize() and don't throw when reset() fails
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed Oct 3, 2021
1 parent 827c098 commit 9763273
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ class GlobalPlannerComponent : public rclcpp::Node
void globalPlanningRequestCallback(
std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::GlobalPlanner>> goal_handle);

// Initialize planning scene monitor and load pipelines
bool init();
// Load and initialized global planner plugin and ROS 2 action and topic interfaces
bool initialize();
};
} // namespace moveit_hybrid_planning
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ GlobalPlannerComponent::GlobalPlannerComponent(const rclcpp::NodeOptions& option
}
else
{
initialized_ = this->init();
initialized_ = this->initialize();
if (!initialized_)
{
timer_->cancel();
Expand All @@ -75,7 +75,7 @@ GlobalPlannerComponent::GlobalPlannerComponent(const rclcpp::NodeOptions& option
});
}

bool GlobalPlannerComponent::init()
bool GlobalPlannerComponent::initialize()
{
auto node_ptr = shared_from_this();

Expand All @@ -92,7 +92,7 @@ bool GlobalPlannerComponent::init()
RCLCPP_INFO(LOGGER, "Received request to cancel global planning goal");
if (!global_planner_instance_->reset())
{
throw std::runtime_error("Failed to reset the global planner while aborting current global planning");
RCLCPP_ERROR(LOGGER, "Failed to reset the global planner while aborting current global planning");
}
return rclcpp_action::CancelResponse::ACCEPT;
},
Expand Down Expand Up @@ -154,7 +154,7 @@ void GlobalPlannerComponent::globalPlanningRequestCallback(
// Reset the global planner
if (!global_planner_instance_->reset())
{
throw std::runtime_error("Failed to reset the global planner");
RCLCPP_ERROR(LOGGER, "Failed to reset the global planner while aborting current global planning");
}
};
} // namespace moveit_hybrid_planning
Expand Down

0 comments on commit 9763273

Please sign in to comment.