moveit2
The MoveIt Motion Planning Framework for ROS 2.
srv_kinematics_plugin.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, JSK, The University of Tokyo.
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 JSK, The University of Tokyo 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: Dave Coleman, Masaki Murooka
36  Desc: Connects MoveIt to any inverse kinematics solver via a ROS service call
37  Supports planning groups with multiple tip frames
38  \todo: better support for mimic joints
39  \todo: better support for redundant joints
40 */
41 
42 #pragma once
43 
44 // ROS2
45 #include <rclcpp/rclcpp.hpp>
46 
47 // System
48 #include <memory>
49 
50 // ROS msgs
51 #include <geometry_msgs/msg/pose.hpp>
52 #include <moveit_msgs/msg/kinematic_solver_info.hpp>
53 #include <moveit_msgs/msg/move_it_error_codes.hpp>
54 
55 // MoveIt
58 
60 {
66 {
67 public:
72 
73  bool
74  getPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
75  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
77 
78  bool searchPositionIK(
79  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
80  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
82 
83  bool searchPositionIK(
84  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
85  const std::vector<double>& consistency_limits, std::vector<double>& solution,
86  moveit_msgs::msg::MoveItErrorCodes& error_code,
88 
89  bool searchPositionIK(
90  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
91  std::vector<double>& solution, const IKCallbackFn& solution_callback,
92  moveit_msgs::msg::MoveItErrorCodes& error_code,
94 
95  bool searchPositionIK(
96  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
97  const std::vector<double>& consistency_limits, std::vector<double>& solution,
98  const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
100 
101  bool searchPositionIK(const std::vector<geometry_msgs::msg::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
102  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
103  const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
105  const moveit::core::RobotState* context_state = nullptr) const override;
106 
107  bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
108  std::vector<geometry_msgs::msg::Pose>& poses) const override;
109 
110  bool initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
111  const std::string& group_name, const std::string& base_name,
112  const std::vector<std::string>& tip_frames, double search_discretization) override;
113 
117  const std::vector<std::string>& getJointNames() const override;
118 
122  const std::vector<std::string>& getLinkNames() const override;
123 
127  const std::vector<std::string>& getVariableNames() const;
128 
129 protected:
130  bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices) override;
131 
132 private:
133  bool timedOut(const rclcpp::Time& start_time, double duration) const;
134 
135  int getJointIndex(const std::string& name) const;
136 
137  bool isRedundantJoint(unsigned int index) const;
138 
139  bool active_;
141  moveit_msgs::msg::KinematicSolverInfo ik_group_info_;
143  unsigned int dimension_;
145  const moveit::core::JointModelGroup* joint_model_group_;
146 
147  moveit::core::RobotStatePtr robot_state_;
148 
149  int num_possible_redundant_joints_;
150 
151  rclcpp::Client<moveit_msgs::srv::GetPositionIK>::SharedPtr ik_service_client_;
152 
153  rclcpp::Node::SharedPtr node_;
154 };
155 } // namespace srv_kinematics_plugin
Provides an interface for kinematics solvers.
std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:76
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...
bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices) override
Set a set of redundant joints for the kinematics solver to use. This can fail, depending on the IK so...
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
bool searchPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
Given a desired pose of the end-effector, search for the joint angles required to reach it....
bool getPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
Given a desired pose of the end-effector, compute the joint angles to reach it.
const std::vector< std::string > & getVariableNames() const
Return all the variable names in the order they are represented internally.
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::msg::Pose > &poses) const override
Given a set of joint angles and a set of links, compute their pose.
bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_name, const std::vector< std::string > &tip_frames, double search_discretization) override
Initialization function for the kinematics, for use with kinematic chain IK solvers.
name
Definition: setup.py:7
A set of options for the kinematics solver.