moveit2
The MoveIt Motion Planning Framework for ROS 2.
move_group_capability.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, 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 Willow Garage 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: Ioan Sucan */
36 
37 #pragma once
38 
44 
45 namespace move_group
46 {
48 {
52  LOOK
53 };
54 
55 MOVEIT_CLASS_FORWARD(MoveGroupCapability); // Defines MoveGroupCapabilityPtr, ConstPtr, WeakPtr... etc
56 
58 {
59 public:
60  explicit MoveGroupCapability(const std::string& capability_name) : capability_name_(capability_name)
61  {
62  }
63 
65  {
66  }
67 
68  void setContext(const MoveGroupContextPtr& context);
69 
70  virtual void initialize() = 0;
71 
72  const std::string& getName() const
73  {
74  return capability_name_;
75  }
76 
77 protected:
78  std::string getActionResultString(const moveit_msgs::msg::MoveItErrorCodes& error_code, bool planned_trajectory_empty,
79  bool plan_only);
80  std::string stateToStr(MoveGroupState state) const;
81 
82  void convertToMsg(const std::vector<plan_execution::ExecutableTrajectory>& trajectory,
83  moveit_msgs::msg::RobotState& first_state_msg,
84  std::vector<moveit_msgs::msg::RobotTrajectory>& trajectory_msg) const;
85  void convertToMsg(const robot_trajectory::RobotTrajectoryPtr& trajectory,
86  moveit_msgs::msg::RobotState& first_state_msg,
87  moveit_msgs::msg::RobotTrajectory& trajectory_msg) const;
88  void convertToMsg(const std::vector<plan_execution::ExecutableTrajectory>& trajectory,
89  moveit_msgs::msg::RobotState& first_state_msg,
90  moveit_msgs::msg::RobotTrajectory& trajectory_msg) const;
91 
94  moveit_msgs::msg::PlanningScene clearSceneRobotState(const moveit_msgs::msg::PlanningScene& scene) const;
95  bool performTransform(geometry_msgs::msg::PoseStamped& pose_msg, const std::string& target_frame) const;
96 
97  planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string& pipeline_id) const;
98 
99  std::string capability_name_;
100  MoveGroupContextPtr context_;
101 };
102 } // namespace move_group
void setContext(const MoveGroupContextPtr &context)
moveit_msgs::msg::PlanningScene clearSceneRobotState(const moveit_msgs::msg::PlanningScene &scene) const
planning_interface::MotionPlanRequest clearRequestStartState(const planning_interface::MotionPlanRequest &request) const
void convertToMsg(const std::vector< plan_execution::ExecutableTrajectory > &trajectory, moveit_msgs::msg::RobotState &first_state_msg, std::vector< moveit_msgs::msg::RobotTrajectory > &trajectory_msg) const
const std::string & getName() const
bool performTransform(geometry_msgs::msg::PoseStamped &pose_msg, const std::string &target_frame) const
std::string getActionResultString(const moveit_msgs::msg::MoveItErrorCodes &error_code, bool planned_trajectory_empty, bool plan_only)
std::string stateToStr(MoveGroupState state) const
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
MoveGroupCapability(const std::string &capability_name)
MOVEIT_CLASS_FORWARD(MoveGroupCapability)
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest