moveit2
The MoveIt Motion Planning Framework for ROS 2.
lma_kinematics_plugin.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2016, CRI group, NTU, Singapore
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 CRI group 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: Francisco Suarez-Ruiz */
36 
37 #pragma once
38 
39 // ROS2
40 #include <rclcpp/rclcpp.hpp>
41 #include <random_numbers/random_numbers.h>
42 
43 // ROS msgs
44 #include <geometry_msgs/msg/pose.hpp>
45 #include <moveit_msgs/srv/get_position_fk.hpp>
46 #include <moveit_msgs/srv/get_position_ik.hpp>
47 #include <moveit_msgs/msg/kinematic_solver_info.hpp>
48 #include <moveit_msgs/msg/move_it_error_codes.hpp>
49 
50 // KDL
51 #include <kdl/config.h>
52 #include <kdl/chainfksolver.hpp>
53 #include <kdl/chainiksolver.hpp>
54 
55 // MoveIt
59 
61 {
67 {
68 public:
73 
74  bool
75  getPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
76  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
78 
79  bool searchPositionIK(
80  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
81  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
83 
84  bool searchPositionIK(
85  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
86  const std::vector<double>& consistency_limits, std::vector<double>& solution,
87  moveit_msgs::msg::MoveItErrorCodes& error_code,
89 
90  bool searchPositionIK(
91  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
92  std::vector<double>& solution, const IKCallbackFn& solution_callback,
93  moveit_msgs::msg::MoveItErrorCodes& error_code,
95 
96  bool searchPositionIK(
97  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
98  const std::vector<double>& consistency_limits, std::vector<double>& solution,
99  const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
101 
102  bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
103  std::vector<geometry_msgs::msg::Pose>& poses) const override;
104 
105  bool initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
106  const std::string& group_name, const std::string& base_frame,
107  const std::vector<std::string>& tip_frames, double search_discretization) override;
108 
112  const std::vector<std::string>& getJointNames() const override;
113 
117  const std::vector<std::string>& getLinkNames() const override;
118 
119 private:
120  bool timedOut(const rclcpp::Time& start_time, double duration) const;
121 
128  bool checkConsistency(const Eigen::VectorXd& seed_state, const std::vector<double>& consistency_limits,
129  const Eigen::VectorXd& solution) const;
131  bool obeysLimits(const Eigen::VectorXd& values) const;
133  void harmonize(Eigen::VectorXd& values) const;
134 
135  void getRandomConfiguration(Eigen::VectorXd& jnt_array) const;
136 
142  void getRandomConfiguration(const Eigen::VectorXd& seed_state, const std::vector<double>& consistency_limits,
143  Eigen::VectorXd& jnt_array) const;
144 
145  bool initialized_;
146 
147  unsigned int dimension_;
148  moveit_msgs::msg::KinematicSolverInfo solver_info_;
149 
150  const moveit::core::JointModelGroup* joint_model_group_;
151  moveit::core::RobotStatePtr state_;
152  KDL::Chain kdl_chain_;
153  std::unique_ptr<KDL::ChainFkSolverPos> fk_solver_;
154  std::vector<const moveit::core::JointModel*> joints_;
155  std::vector<std::string> joint_names_;
156  rclcpp::Node::SharedPtr node_;
157 
158  int max_solver_iterations_;
159  double epsilon_;
165  double orientation_vs_position_weight_;
166 };
167 } // namespace lma_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.
Implementation of kinematics using Levenberg-Marquardt (LMA) solver from KDL. This version supports a...
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override
Initialization function for the kinematics, for use with kinematic chain IK solvers.
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.
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 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....
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:76
A set of options for the kinematics solver.