This file is indexed.

/usr/include/kdl/chainiksolver.hpp is in liborocos-kdl-dev 1.3.1+dfsg-1.

This file is owned by root:root, with mode 0o644.

The actual contents of the file can be viewed below.

  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
// Copyright  (C)  2007  Ruben Smits <ruben dot smits at mech dot kuleuven dot be>

// Version: 1.0
// Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
// Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
// URL: http://www.orocos.org/kdl

// This library is free software; you can redistribute it and/or
// modify it under the terms of the GNU Lesser General Public
// License as published by the Free Software Foundation; either
// version 2.1 of the License, or (at your option) any later version.

// This library is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
// Lesser General Public License for more details.

// You should have received a copy of the GNU Lesser General Public
// License along with this library; if not, write to the Free Software
// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA

#ifndef KDL_CHAIN_IKSOLVER_HPP
#define KDL_CHAIN_IKSOLVER_HPP

#include "chain.hpp"
#include "frames.hpp"
#include "framevel.hpp"
#include "frameacc.hpp"
#include "jntarray.hpp"
#include "jntarrayvel.hpp"
#include "jntarrayacc.hpp"
#include "solveri.hpp"

namespace KDL {

    /**
	  * \brief This <strong>abstract</strong> class encapsulates the inverse
	  * position solver for a KDL::Chain.
     *
     * @ingroup KinematicFamily
     */
    class ChainIkSolverPos : public KDL::SolverI {
    public:
        /**
         * Calculate inverse position kinematics, from cartesian
         *coordinates to joint coordinates.
         *
         * @param q_init initial guess of the joint coordinates
         * @param p_in input cartesian coordinates
         * @param q_out output joint coordinates
         *
         * @return if < 0 something went wrong
         */
        virtual int CartToJnt(const JntArray& q_init, const Frame& p_in, JntArray& q_out)=0;

        virtual ~ChainIkSolverPos(){};
    };

    /**
	  * \brief This <strong>abstract</strong> class encapsulates the inverse
	  * velocity solver for a KDL::Chain.
     *
     * @ingroup KinematicFamily
     */
    class ChainIkSolverVel : public KDL::SolverI {
    public:
        /**
         * Calculate inverse velocity kinematics, from joint positions
         *and cartesian velocity to joint velocities.
         *
         * @param q_in input joint positions
         * @param v_in input cartesian velocity
         * @param qdot_out output joint velocities
         *
         * @return if < 0 something went wrong
         */
        virtual int CartToJnt(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out)=0;
        /**
         * Calculate inverse position and velocity kinematics, from
         *cartesian position and velocity to joint positions and velocities.
         *
         * @param q_init initial joint positions
         * @param v_in input cartesian position and velocity
         * @param q_out output joint position and velocity
         *
         * @return if < 0 something went wrong
         */
        virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out)=0;

        virtual ~ChainIkSolverVel(){};

    };

    /**
	  * \brief This <strong>abstract</strong> class encapsulates the inverse
	  * acceleration solver for a KDL::Chain.
     *
     * @ingroup KinematicFamily
     */

    class ChainIkSolverAcc : public KDL::SolverI {
    public:
        /**
         * Calculate inverse acceleration kinematics from joint
         * positions, joint velocities and cartesian acceleration to joint accelerations.
         *
         * @param q_in input joint positions
         * @param qdot_in input joint velocities
         * @param a_in input cartesian acceleration
         * @param qdotdot_out output joint accelerations
         *
         * @return if < 0 something went wrong
         */
        virtual int CartToJnt(const JntArray& q_in, const JntArray& qdot_in, const Twist a_in,
                         JntArray& qdotdot_out)=0;
        /**
         * Calculate inverse position, velocity and acceration
         *kinematics from cartesian coordinates to joint coordinates
         *
         * @param q_init initial guess for joint positions
         * @param a_in input cartesian position, velocity and acceleration
         * @param q_out output joint position, velocity and acceleration
         *
         * @return if < 0 something went wrong
         */
        virtual int CartTojnt(const JntArray& q_init, const FrameAcc& a_in,
                         JntArrayAcc& q_out)=0;

        /**
         * Calculate inverse velocity and acceleration kinematics from
         * joint positions and cartesian velocity and acceleration to
         * joint velocities and accelerations.
         *
         * @param q_in input joint positions
         * @param v_in input cartesian velocity
         * @param a_in input cartesian acceleration
         * @param qdot_out output joint velocities
         * @param qdotdot_out output joint accelerations
         *
         * @return if < 0 something went wrong
         */
        virtual int CartToJnt(const JntArray& q_in, const Twist& v_in, const Twist& a_in,
                         JntArray& qdot_out, JntArray& qdotdot_out)=0;
        /**
         * Calculate inverse position and acceleration kinematics from
         *joint velocities and cartesian position and acceleration to
         *joint positions and accelerations
         *
         * @param q_init initial guess for joint positions
         * @param p_in input cartesian position
         * @param qdot_in input joint velocities
         * @param a_in input cartesian acceleration
         * @param q_out output joint positions
         * @param qdotdot_out output joint accelerations
         *
         * @return if < 0 something went wrong
         */
        virtual int CartTojnt(const JntArray& q_init, const Frame& p_in, const JntArray& qdot_in, const Twist& a_in,
                         JntArray& q_out, JntArray& qdotdot_out)=0;

        virtual ~ChainIkSolverAcc(){};
    };


}//end of namespace KDL

#endif