moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajopt_planner_manager.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, PickNik Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PickNik Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Omid Heidari
36  Desc: TrajOpt planning plugin
37 */
38 
40 
42 
43 #include <class_loader/class_loader.hpp>
44 
46 
47 namespace trajopt_interface
48 {
50 {
51 public:
53  {
54  }
55 
56  bool initialize(const moveit::core::RobotModelConstPtr& model, const std::string& ns) override
57  {
58  ROS_INFO(" ======================================= initialize gets called");
59 
60  if (!ns.empty())
61  nh_ = ros::NodeHandle(ns);
62  std::string trajopt_ns = ns.empty() ? "trajopt" : ns + "/trajopt";
63 
64  for (const std::string& gpName : model->getJointModelGroupNames())
65  {
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);
69  }
70 
71  return true;
72  }
73 
74  bool canServiceRequest(const moveit_msgs::MotionPlanRequest& req) const override
75  {
76  return req.trajectory_constraints.constraints.empty();
77  }
78 
79  std::string getDescription() const override
80  {
81  return "TrajOpt";
82  }
83 
84  void getPlanningAlgorithms(std::vector<std::string>& algs) const override
85  {
86  algs.clear();
87  algs.push_back("trajopt");
88  }
89 
90  planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
92  moveit_msgs::MoveItErrorCodes& error_code) const override
93  {
94  ROS_INFO(" ======================================= getPlanningContext() is called ");
95  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
96 
97  if (req.group_name.empty())
98  {
99  ROS_ERROR("No group specified to plan for");
100  error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
101  return planning_interface::PlanningContextPtr();
102  }
103 
104  if (!planning_scene)
105  {
106  ROS_ERROR("No planning scene supplied as input");
107  error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
108  return planning_interface::PlanningContextPtr();
109  }
110 
111  // create PlanningScene using hybrid collision detector
112  planning_scene::PlanningScenePtr ps = planning_scene->diff();
113 
114  // set FCL for the collision
115  ps->allocateCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create());
116 
117  // retrieve and configure existing context
118  const TrajOptPlanningContextPtr& context = planning_contexts_.at(req.group_name);
119 
120  ROS_INFO(" ======================================= context is made ");
121 
122  context->setPlanningScene(ps);
123  context->setMotionPlanRequest(req);
124 
125  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
126 
127  return context;
128  }
129 
130 private:
131  ros::NodeHandle nh_;
132 
133 protected:
134  std::map<std::string, TrajOptPlanningContextPtr> planning_contexts_;
135 };
136 
137 } // namespace trajopt_interface
138 
139 // register the TrajOptPlannerManager class as a plugin
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)