43 #include <class_loader/class_loader.hpp>
56 bool initialize(
const moveit::core::RobotModelConstPtr& model,
const std::string& ns)
override
58 ROS_INFO(
" ======================================= initialize gets called");
61 nh_ = ros::NodeHandle(ns);
62 std::string trajopt_ns = ns.empty() ?
"trajopt" : ns +
"/trajopt";
64 for (
const std::string& gpName : model->getJointModelGroupNames())
66 ROS_INFO(
" ======================================= group name: %s, robot model: %s", gpName.c_str(),
67 model->getName().c_str());
68 planning_contexts_[gpName] = std::make_shared<TrajOptPlanningContext>(
"trajopt_planning_context", gpName, model);
76 return req.trajectory_constraints.constraints.empty();
87 algs.push_back(
"trajopt");
92 moveit_msgs::MoveItErrorCodes& error_code)
const override
94 ROS_INFO(
" ======================================= getPlanningContext() is called ");
95 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
97 if (req.group_name.empty())
99 ROS_ERROR(
"No group specified to plan for");
100 error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
101 return planning_interface::PlanningContextPtr();
106 ROS_ERROR(
"No planning scene supplied as input");
107 error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
108 return planning_interface::PlanningContextPtr();
120 ROS_INFO(
" ======================================= context is made ");
122 context->setPlanningScene(ps);
123 context->setMotionPlanRequest(req);
125 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
static CollisionDetectorAllocatorPtr create()
Base class for a MoveIt planner.
planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const override
std::map< std::string, TrajOptPlanningContextPtr > planning_contexts_
bool initialize(const moveit::core::RobotModelConstPtr &model, const std::string &ns) override
std::string getDescription() const override
Get.
bool canServiceRequest(const moveit_msgs::MotionPlanRequest &req) const override
void getPlanningAlgorithms(std::vector< std::string > &algs) const override
Get the names of the known planning algorithms (values that can be filled as planner_id in the planni...
This namespace includes the base class for MoveIt planners.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)