moveit2
The MoveIt Motion Planning Framework for ROS 2.
kinematics_constraint_aware.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2012, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Sachin Chitta
36  *********************************************************************/
37 
38 #pragma once
39 
40 // ROS msgs
41 #include <moveit_msgs/GetConstraintAwarePositionIK.h>
42 #include <geometry_msgs/PoseStamped.h>
43 #include <moveit_msgs/msg/move_it_error_codes.hpp>
44 #include <moveit_msgs/msg/constraints.hpp>
45 #include <moveit_msgs/msg/robot_state.hpp>
46 
47 // Plugin
49 
50 // MoveIt
56 
58 {
60 typedef std::shared_ptr<KinematicsConstraintAware> KinematicsConstraintAwarePtr;
61 typedef std::shared_ptr<const KinematicsConstraintAware> KinematicsConstraintAwareConstPtr;
62 
67 {
68 public:
74  KinematicsConstraintAware(const moveit::core::RobotModelConstPtr& kinematic_model, const std::string& group_name);
75 
82  bool getIK(const planning_scene::PlanningSceneConstPtr& planning_scene,
85 
92  bool getIK(const planning_scene::PlanningSceneConstPtr& planning_scene,
93  const moveit_msgs::msg::GetConstraintAwarePositionIK::Request& request,
94  moveit_msgs::msg::GetConstraintAwarePositionIK::Response& response) const;
95 
96  const std::string& getGroupName() const
97  {
98  return group_name_;
99  }
100 
101  const moveit::core::RobotModelConstPtr& getRobotModel() const
102  {
103  return kinematic_model_;
104  }
105 
106 private:
107  EigenSTL::vector_Isometry3d transformPoses(const planning_scene::PlanningSceneConstPtr& planning_scene,
108  const moveit::core::RobotState& kinematic_state,
109  const std::vector<geometry_msgs::PoseStamped>& poses,
110  const std::string& target_frame) const;
111 
112  bool convertServiceRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
113  const moveit_msgs::msg::GetConstraintAwarePositionIK::Request& request,
115  kinematics_constraint_aware::KinematicsResponse& kinematics_response) const;
116 
117  geometry_msgs::Pose getTipFramePose(const planning_scene::PlanningSceneConstPtr& planning_scene,
118  const moveit::core::RobotState& kinematic_state, const geometry_msgs::Pose& pose,
119  const std::string& link_name, unsigned int sub_group_index) const;
120 
121  bool validityCallbackFn(const planning_scene::PlanningSceneConstPtr& planning_scene,
124  moveit::core::JointStateGroup* joint_state_group,
125  const std::vector<double>& joint_group_variable_values) const;
126 
127  std::vector<std::string> sub_groups_names_;
128 
129  moveit::core::RobotModelConstPtr kinematic_model_;
130 
131  const moveit::core::JointModelGroup* joint_model_group_;
132 
133  std::string group_name_;
134 
135  bool has_sub_groups_;
136 
137  unsigned int ik_attempts_;
138 };
139 } // namespace kinematics_constraint_aware
KinematicsConstraintAware(const moveit::core::RobotModelConstPtr &kinematic_model, const std::string &group_name)
Default constructor.
bool getIK(const planning_scene::PlanningSceneConstPtr &planning_scene, const kinematics_constraint_aware::KinematicsRequest &request, kinematics_constraint_aware::KinematicsResponse &response) const
Solve the planning problem.
const moveit::core::RobotModelConstPtr & getRobotModel() const
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
std::shared_ptr< KinematicsConstraintAware > KinematicsConstraintAwarePtr
std::shared_ptr< const KinematicsConstraintAware > KinematicsConstraintAwareConstPtr
This namespace includes the central class for representing planning contexts.