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 #ifndef MOVEIT_KINEMATICS_CONSTRAINT_AWARE_
39 #define MOVEIT_KINEMATICS_CONSTRAINT_AWARE_
40 
41 // System
42 #include <boost/shared_ptr.hpp>
43 #include <boost/function.hpp>
44 
45 // ROS msgs
46 #include <moveit_msgs/GetConstraintAwarePositionIK.h>
47 #include <geometry_msgs/PoseStamped.h>
48 #include <moveit_msgs/MoveItErrorCodes.h>
49 #include <moveit_msgs/Constraints.h>
50 #include <moveit_msgs/RobotState.h>
51 
52 // Plugin
53 #include <moveit/kinematics_base/kinematics_base.h>
54 
55 // MoveIt!
56 #include <moveit/robot_model/robot_model.h>
57 #include <moveit/robot_state/robot_state.h>
58 #include <moveit/planning_scene/planning_scene.h>
59 #include <moveit/kinematic_constraints/kinematic_constraint.h>
61 
63 {
65 typedef boost::shared_ptr<KinematicsConstraintAware> KinematicsConstraintAwarePtr;
66 typedef boost::shared_ptr<const KinematicsConstraintAware> KinematicsConstraintAwareConstPtr;
67 
72 {
73 public:
79  KinematicsConstraintAware(const robot_model::RobotModelConstPtr& kinematic_model, const std::string& group_name);
80 
87  bool getIK(const planning_scene::PlanningSceneConstPtr& planning_scene,
90 
97  bool getIK(const planning_scene::PlanningSceneConstPtr& planning_scene,
98  const moveit_msgs::GetConstraintAwarePositionIK::Request& request,
99  moveit_msgs::GetConstraintAwarePositionIK::Response& response) const;
100 
101  const std::string& getGroupName() const
102  {
103  return group_name_;
104  }
105 
106  const robot_model::RobotModelConstPtr& getRobotModel() const
107  {
108  return kinematic_model_;
109  }
110 
111 private:
112  EigenSTL::vector_Affine3d transformPoses(const planning_scene::PlanningSceneConstPtr& planning_scene,
113  const robot_state::RobotState& kinematic_state,
114  const std::vector<geometry_msgs::PoseStamped>& poses,
115  const std::string& target_frame) const;
116 
117  bool convertServiceRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
118  const moveit_msgs::GetConstraintAwarePositionIK::Request& request,
120  kinematics_constraint_aware::KinematicsResponse& kinematics_response) const;
121 
122  geometry_msgs::Pose getTipFramePose(const planning_scene::PlanningSceneConstPtr& planning_scene,
123  const robot_state::RobotState& kinematic_state, const geometry_msgs::Pose& pose,
124  const std::string& link_name, unsigned int sub_group_index) const;
125 
126  bool validityCallbackFn(const planning_scene::PlanningSceneConstPtr& planning_scene,
129  robot_state::JointStateGroup* joint_state_group,
130  const std::vector<double>& joint_group_variable_values) const;
131 
132  std::vector<std::string> sub_groups_names_;
133 
134  robot_model::RobotModelConstPtr kinematic_model_;
135 
136  const robot_model::JointModelGroup* joint_model_group_;
137 
138  std::string group_name_;
139 
141 
142  unsigned int ik_attempts_;
143 };
144 }
145 
146 #endif
EigenSTL::vector_Affine3d transformPoses(const planning_scene::PlanningSceneConstPtr &planning_scene, const robot_state::RobotState &kinematic_state, const std::vector< geometry_msgs::PoseStamped > &poses, const std::string &target_frame) const
boost::shared_ptr< KinematicsConstraintAware > KinematicsConstraintAwarePtr
const robot_model::RobotModelConstPtr & getRobotModel() const
boost::shared_ptr< const KinematicsConstraintAware > KinematicsConstraintAwareConstPtr
bool convertServiceRequest(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::GetConstraintAwarePositionIK::Request &request, kinematics_constraint_aware::KinematicsRequest &kinematics_request, kinematics_constraint_aware::KinematicsResponse &kinematics_response) const
bool getIK(const planning_scene::PlanningSceneConstPtr &planning_scene, const kinematics_constraint_aware::KinematicsRequest &request, kinematics_constraint_aware::KinematicsResponse &response) const
Solve the planning problem.
bool validityCallbackFn(const planning_scene::PlanningSceneConstPtr &planning_scene, const kinematics_constraint_aware::KinematicsRequest &request, kinematics_constraint_aware::KinematicsResponse &response, robot_state::JointStateGroup *joint_state_group, const std::vector< double > &joint_group_variable_values) const
geometry_msgs::Pose getTipFramePose(const planning_scene::PlanningSceneConstPtr &planning_scene, const robot_state::RobotState &kinematic_state, const geometry_msgs::Pose &pose, const std::string &link_name, unsigned int sub_group_index) const
KinematicsConstraintAware(const robot_model::RobotModelConstPtr &kinematic_model, const std::string &group_name)
Default constructor.


moveit_experimental
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley , Jorge Nicho
autogenerated on Wed Jul 10 2019 04:03:02