40 const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"hybrid_planning_manager");
54 return ReactionResult(event,
"", moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
58 return ReactionResult(event,
"'ReplanInvalidatedTrajectory' plugin cannot handle this event.",
59 moveit_msgs::msg::MoveItErrorCodes::FAILURE);
64 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
std::shared_ptr< HybridPlanningManager > hybrid_planning_manager_
ReactionResult react(const std::string &event) override
constexpr std::string_view toString(const LocalFeedbackEnum &code)
const rclcpp::Logger LOGGER