40 #include <rclcpp/rclcpp.hpp>
41 #include <random_numbers/random_numbers.h>
42 #include <lma_kinematics_parameters.hpp>
45 #include <geometry_msgs/msg/pose.hpp>
46 #include <moveit_msgs/srv/get_position_fk.hpp>
47 #include <moveit_msgs/srv/get_position_ik.hpp>
48 #include <moveit_msgs/msg/kinematic_solver_info.hpp>
49 #include <moveit_msgs/msg/move_it_error_codes.hpp>
52 #include <kdl/config.h>
53 #include <kdl/chainfksolver.hpp>
54 #include <kdl/chainiksolver.hpp>
76 getPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
77 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
81 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
82 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
86 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
87 const std::vector<double>& consistency_limits, std::vector<double>& solution,
88 moveit_msgs::msg::MoveItErrorCodes& error_code,
92 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
93 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
94 moveit_msgs::msg::MoveItErrorCodes& error_code,
98 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
99 const std::vector<double>& consistency_limits, std::vector<double>& solution,
100 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
103 bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
104 std::vector<geometry_msgs::msg::Pose>& poses)
const override;
107 const std::string& group_name,
const std::string& base_frame,
108 const std::vector<std::string>& tip_frames,
double search_discretization)
override;
113 const std::vector<std::string>&
getJointNames()
const override;
118 const std::vector<std::string>&
getLinkNames()
const override;
121 bool timedOut(
const rclcpp::Time& start_time,
double duration)
const;
129 bool checkConsistency(
const Eigen::VectorXd& seed_state,
const std::vector<double>& consistency_limits,
130 const Eigen::VectorXd& solution)
const;
132 bool obeysLimits(
const Eigen::VectorXd& values)
const;
134 void harmonize(Eigen::VectorXd& values)
const;
136 void getRandomConfiguration(Eigen::VectorXd& jnt_array)
const;
143 void getRandomConfiguration(
const Eigen::VectorXd& seed_state,
const std::vector<double>& consistency_limits,
144 Eigen::VectorXd& jnt_array)
const;
148 unsigned int dimension_;
149 moveit_msgs::msg::KinematicSolverInfo solver_info_;
152 moveit::core::RobotStatePtr state_;
153 KDL::Chain kdl_chain_;
154 std::unique_ptr<KDL::ChainFkSolverPos> fk_solver_;
155 std::vector<const moveit::core::JointModel*> joints_;
156 std::vector<std::string> joint_names_;
157 rclcpp::Node::SharedPtr node_;
159 std::shared_ptr<lma_kinematics::ParamListener> param_listener_;
160 lma_kinematics::Params params_;
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.
LMAKinematicsPlugin()
Default constructor.
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...
A set of options for the kinematics solver.