Skip to content

Commit

Permalink
Clean-up hybrid planning package (#2603)
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr authored Jan 31, 2024
1 parent 3d16b4a commit c19b1eb
Show file tree
Hide file tree
Showing 24 changed files with 353 additions and 855 deletions.
6 changes: 5 additions & 1 deletion moveit_ros/hybrid_planning/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ moveit_package()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(generate_parameter_library REQUIRED)
find_package(moveit_core REQUIRED)
find_package(moveit_msgs REQUIRED)
find_package(moveit_ros_planning REQUIRED)
Expand All @@ -31,6 +32,9 @@ set(LIBRARIES
replan_invalidated_trajectory_plugin
simple_sampler_plugin
single_plan_execution_plugin
# Parameters
local_planner_parameters
hp_manager_parameters
)

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down Expand Up @@ -75,7 +79,7 @@ install(TARGETS ${LIBRARIES}
RUNTIME DESTINATION bin
INCLUDES DESTINATION include/moveit_hybrid_planning)

install(TARGETS cancel_action hybrid_planning_demo_node
install(TARGETS cancel_action
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/moveit_hybrid_planning
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,17 +62,9 @@ GlobalPlannerComponent::GlobalPlannerComponent(const rclcpp::NodeOptions& option
bool GlobalPlannerComponent::initializeGlobalPlanner()
{
// Initialize global planning request action server
std::string global_planning_action_name = "";
node_->declare_parameter("global_planning_action_name", "");
node_->get_parameter<std::string>("global_planning_action_name", global_planning_action_name);
if (global_planning_action_name.empty())
{
RCLCPP_ERROR(node_->get_logger(), "global_planning_action_name was not defined");
return false;
}
cb_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
global_planning_request_server_ = rclcpp_action::create_server<moveit_msgs::action::GlobalPlanner>(
node_, global_planning_action_name,
node_, "global_planning_action",
// Goal callback
[this](const rclcpp_action::GoalUUID& /*unused*/,
const std::shared_ptr<const moveit_msgs::action::GlobalPlanner::Goal>& /*unused*/) {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
# Hybrid planning manager component
generate_parameter_library(hp_manager_parameters res/hp_manager_parameters.yaml)
add_library(moveit_hybrid_planning_manager SHARED src/hybrid_planning_manager.cpp)
set_target_properties(moveit_hybrid_planning_manager PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
target_link_libraries(moveit_hybrid_planning_manager hp_manager_parameters)
ament_target_dependencies(moveit_hybrid_planning_manager ${THIS_PACKAGE_INCLUDE_DEPENDS})
Original file line number Diff line number Diff line change
Expand Up @@ -50,13 +50,27 @@ enum class HybridPlanningEvent
GLOBAL_PLANNING_ACTION_SUCCESSFUL,
GLOBAL_PLANNING_ACTION_ABORTED,
GLOBAL_PLANNING_ACTION_CANCELED,
GLOBAL_PLANNING_ACTION_REJECTED,
// Indicates that the global planner found a solution (This solution is not necessarily the last or best solution)
GLOBAL_SOLUTION_AVAILABLE,
// Result of the local planning action
LOCAL_PLANNING_ACTION_SUCCESSFUL,
LOCAL_PLANNING_ACTION_ABORTED,
LOCAL_PLANNING_ACTION_CANCELED,
LOCAL_PLANNING_ACTION_REJECTED,
// Undefined event to allow empty reaction events to indicate failure
UNDEFINED
};

/**
* Enum class HybridPlanningAction - This class defines the basic actions that the HP manager can perform
*/
enum class HybridPlanningAction
{
DO_NOTHING,
RETURN_HP_SUCCESS,
RETURN_HP_FAILURE,
SEND_GLOBAL_SOLVER_REQUEST,
SEND_LOCAL_SOLVER_REQUEST
};
} // namespace moveit::hybrid_planning
Original file line number Diff line number Diff line change
Expand Up @@ -54,14 +54,14 @@ namespace moveit::hybrid_planning
/**
* Class HybridPlanningManager - ROS 2 component node that implements the hybrid planning manager.
*/
class HybridPlanningManager : public rclcpp::Node
class HybridPlanningManager
{
public:
/** \brief Constructor */
HybridPlanningManager(const rclcpp::NodeOptions& options);

/** \brief Destructor */
~HybridPlanningManager() override
~HybridPlanningManager()
{
// Join the thread used for long-running callbacks
if (long_callback_thread_.joinable())
Expand All @@ -70,21 +70,19 @@ class HybridPlanningManager : public rclcpp::Node
}
}

/**
* Allows creation of a smart pointer that references to instances of this object
* @return shared pointer of the HybridPlanningManager instance that called the function
*/
std::shared_ptr<HybridPlanningManager> shared_from_this()
{
return std::static_pointer_cast<HybridPlanningManager>(Node::shared_from_this());
}

/**
* Load and initialized planner logic plugin and ROS 2 action and topic interfaces
* @return Initialization successful yes/no
*/
bool initialize();

// This function is required to make this class a valid NodeClass
// see https://docs.ros2.org/latest/api/rclcpp_components/register__node__macro_8hpp.html
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() // NOLINT
{
return node_->get_node_base_interface(); // NOLINT
}

/**
* Cancel any active action goals, including global and local planners
*/
Expand Down Expand Up @@ -115,19 +113,22 @@ class HybridPlanningManager : public rclcpp::Node
*/
void sendHybridPlanningResponse(bool success);

/**
* @brief Process the action result and do an action call if necessary
*
* @param result Result to an event
*/
void processReactionResult(const ReactionResult& result);

private:
std::shared_ptr<rclcpp::Node> node_;

// Planner logic plugin loader
std::unique_ptr<pluginlib::ClassLoader<PlannerLogicInterface>> planner_logic_plugin_loader_;

// Planner logic instance to implement reactive behavior
std::shared_ptr<PlannerLogicInterface> planner_logic_instance_;

// Timer to trigger events periodically
rclcpp::TimerBase::SharedPtr timer_;

// Flag that indicates whether the manager is initialized
bool initialized_;

// Flag that indicates hybrid planning has been canceled
std::atomic<bool> stop_hybrid_planning_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,9 @@ namespace moveit::hybrid_planning
// Describes the outcome of a reaction to an event in the hybrid planning architecture
struct ReactionResult
{
ReactionResult(const HybridPlanningEvent& planning_event, const std::string& error_msg, int error_code)
: error_message(error_msg), error_code(error_code)
ReactionResult(const HybridPlanningEvent& planning_event, const std::string& error_msg, const int error_code,
const HybridPlanningAction& action = HybridPlanningAction::DO_NOTHING)
: error_message(error_msg), error_code(error_code), action(action)
{
switch (planning_event)
{
Expand Down Expand Up @@ -79,10 +80,18 @@ struct ReactionResult
break;
case HybridPlanningEvent::UNDEFINED:
event = "Undefined event";
break;
case HybridPlanningEvent::GLOBAL_PLANNING_ACTION_REJECTED:
event = "Global planning action rejected";
break;
case HybridPlanningEvent::LOCAL_PLANNING_ACTION_REJECTED:
event = "Local planning action rejected";
break;
}
};
ReactionResult(const std::string& event, const std::string& error_msg, int error_code)
: event(event), error_message(error_msg), error_code(error_code){};
ReactionResult(const std::string& event, const std::string& error_msg, const int error_code,
const HybridPlanningAction& action = HybridPlanningAction::DO_NOTHING)
: event(event), error_message(error_msg), error_code(error_code), action(action){};

// Event that triggered the reaction
std::string event;
Expand All @@ -92,9 +101,10 @@ struct ReactionResult

// Error code
MoveItErrorCode error_code;
};

class HybridPlanningManager; // Forward declaration
// Action to that needs to be performed by the HP manager
HybridPlanningAction action;
};

/**
* Class PlannerLogicInterface - Base class for a planner logic. The logic defines how to react to different events that
Expand All @@ -113,10 +123,12 @@ class PlannerLogicInterface

/**
* Initialize the planner logic
* @param hybrid_planning_manager The hybrid planning manager instance to initialize this logic with.
* @return true if initialization was successful
*/
virtual bool initialize(const std::shared_ptr<HybridPlanningManager>& hybrid_planning_manager) = 0;
virtual bool initialize()
{
return true;
};

/**
* React to event defined in HybridPlanningEvent enum
Expand All @@ -131,9 +143,5 @@ class PlannerLogicInterface
* @return Reaction result that summarizes the outcome of the reaction
*/
virtual ReactionResult react(const std::string& event) = 0;

protected:
// The hybrid planning manager instance that runs this logic plugin
std::shared_ptr<HybridPlanningManager> hybrid_planning_manager_ = nullptr;
};
} // namespace moveit::hybrid_planning
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
hp_manager_parameters:
planner_logic_plugin_name: {
type: string,
description: "Name of the planner logic plugin",
default_value: "moveit::hybrid_planning/ReplanInvalidatedTrajectory",
}
Loading

0 comments on commit c19b1eb

Please sign in to comment.