moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
chainiksolver_vel_mimic_svd.hpp
Go to the documentation of this file.
1// Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
2
3// Version: 1.0
4// Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
5// Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
6// URL: http://www.orocos.org/kdl
7
8// This library is free software; you can redistribute it and/or
9// modify it under the terms of the GNU Lesser General Public
10// License as published by the Free Software Foundation; either
11// version 2.1 of the License, or (at your option) any later version.
12
13// This library is distributed in the hope that it will be useful,
14// but WITHOUT ANY WARRANTY; without even the implied warranty of
15// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
16// Lesser General Public License for more details.
17
18// You should have received a copy of the GNU Lesser General Public
19// License along with this library; if not, write to the Free Software
20// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
21
22// Modified to account for "mimic" joints, i.e. joints whose motion has a
23// linear relationship to that of another joint.
24// Copyright (C) 2013 Sachin Chitta, Willow Garage
25
26#pragma once
27
28#include <kdl/config.h>
29#include <kdl/chainiksolver.hpp>
30#include <kdl/chainjnttojacsolver.hpp>
31
33#include <Eigen/SVD>
34
35namespace KDL
36{
46class ChainIkSolverVelMimicSVD : public ChainIkSolverVel
47{
48public:
61 explicit ChainIkSolverVelMimicSVD(const Chain& chain_,
62 const std::vector<kdl_kinematics_plugin::JointMimic>& mimic_joints,
63 bool position_ik = false, double threshold = 0.001);
64
65 void updateInternalDataStructures() override;
66
68
69 int CartToJnt(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out) override
70 {
71 return CartToJnt(q_in, v_in, qdot_out, Eigen::VectorXd::Constant(svd_.cols(), 1.0),
72 Eigen::Matrix<double, 6, 1>::Constant(1.0));
73 }
74
79 // NOLINTNEXTLINE(readability-identifier-naming)
80 int CartToJnt(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out, const Eigen::VectorXd& joint_weights,
81 const Eigen::Matrix<double, 6, 1>& cartesian_weights);
82
84 int CartToJnt(const JntArray& /*q_init*/, const FrameVel& /*v_in*/, JntArrayVel& /*q_out*/) override
85 {
86 return -1;
87 }
88
90 bool isPositionOnly() const
91 {
92 return svd_.rows() == 3;
93 }
94
95private:
96 bool jacToJacReduced(const Jacobian& jac, Jacobian& jac_reduced);
97
98 // Mimic joint specific
99 const std::vector<kdl_kinematics_plugin::JointMimic>& mimic_joints_;
100 int num_mimic_joints_;
101
102 const Chain& chain_;
103 ChainJntToJacSolver jnt2jac_;
104
105 Eigen::JacobiSVD<Eigen::MatrixXd> svd_;
106 Eigen::VectorXd qdot_out_reduced_;
107
108 Jacobian jac_; // full Jacobian
109 Jacobian jac_reduced_; // reduced Jacobian with contributions of mimic joints mapped onto active DoFs
110};
111} // namespace KDL
int CartToJnt(const JntArray &q_in, const Twist &v_in, JntArray &qdot_out) override
int CartToJnt(const JntArray &, const FrameVel &, JntArrayVel &) override
not implemented.
bool isPositionOnly() const
Return true iff we ignore orientation but only consider position for inverse kinematics.