/usr/include/kdl/joint.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 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 | // 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_JOINT_HPP
#define KDL_JOINT_HPP
#include "frames.hpp"
#include <string>
#include <exception>
namespace KDL {
/**
* \brief This class encapsulates a simple joint, that is with one
* parameterized degree of freedom and with scalar dynamic properties.
*
* A simple joint is described by the following properties :
* - scale: ratio between motion input and motion output
* - offset: between the "physical" and the "logical" zero position.
* - type: revolute or translational, along one of the basic frame axes
* - inertia, stiffness and damping: scalars representing the physical
* effects along/about the joint axis only.
*
* @ingroup KinematicFamily
*/
class Joint {
public:
typedef enum { RotAxis,RotX,RotY,RotZ,TransAxis,TransX,TransY,TransZ,None} JointType;
/**
* Constructor of a joint.
*
* @param name of the joint
* @param type type of the joint, default: Joint::None
* @param scale scale between joint input and actual geometric
* movement, default: 1
* @param offset offset between joint input and actual
* geometric input, default: 0
* @param inertia 1D inertia along the joint axis, default: 0
* @param damping 1D damping along the joint axis, default: 0
* @param stiffness 1D stiffness along the joint axis,
* default: 0
*/
explicit Joint(const std::string& name, const JointType& type=None,const double& scale=1,const double& offset=0,
const double& inertia=0,const double& damping=0,const double& stiffness=0);
/**
* Constructor of a joint.
*
* @param type type of the joint, default: Joint::None
* @param scale scale between joint input and actual geometric
* movement, default: 1
* @param offset offset between joint input and actual
* geometric input, default: 0
* @param inertia 1D inertia along the joint axis, default: 0
* @param damping 1D damping along the joint axis, default: 0
* @param stiffness 1D stiffness along the joint axis,
* default: 0
*/
explicit Joint(const JointType& type=None,const double& scale=1,const double& offset=0,
const double& inertia=0,const double& damping=0,const double& stiffness=0);
/**
* Constructor of a joint.
*
* @param name of the joint
* @param origin the origin of the joint
* @param axis the axis of the joint
* @param scale scale between joint input and actual geometric
* movement, default: 1
* @param offset offset between joint input and actual
* geometric input, default: 0
* @param inertia 1D inertia along the joint axis, default: 0
* @param damping 1D damping along the joint axis, default: 0
* @param stiffness 1D stiffness along the joint axis,
* default: 0
*/
Joint(const std::string& name, const Vector& _origin, const Vector& _axis, const JointType& type, const double& _scale=1, const double& _offset=0,
const double& _inertia=0, const double& _damping=0, const double& _stiffness=0);
/**
* Constructor of a joint.
*
* @param origin the origin of the joint
* @param axis the axis of the joint
* @param scale scale between joint input and actual geometric
* movement, default: 1
* @param offset offset between joint input and actual
* geometric input, default: 0
* @param inertia 1D inertia along the joint axis, default: 0
* @param damping 1D damping along the joint axis, default: 0
* @param stiffness 1D stiffness along the joint axis,
* default: 0
*/
Joint(const Vector& _origin, const Vector& _axis, const JointType& type, const double& _scale=1, const double& _offset=0,
const double& _inertia=0, const double& _damping=0, const double& _stiffness=0);
/**
* Request the 6D-pose between the beginning and the end of
* the joint at joint position q
*
* @param q the 1D joint position
*
* @return the resulting 6D-pose
*/
Frame pose(const double& q)const;
/**
* Request the resulting 6D-velocity with a joint velocity qdot
*
* @param qdot the 1D joint velocity
*
* @return the resulting 6D-velocity
*/
Twist twist(const double& qdot)const;
/**
* Request the Vector corresponding to the axis of a revolute joint.
*
* @return Vector. e.g (1,0,0) for RotX etc.
*/
Vector JointAxis() const;
/**
* Request the Vector corresponding to the origin of a revolute joint.
*
* @return Vector
*/
Vector JointOrigin() const;
/**
* Request the name of the joint
*
*
* @return const reference to the name of the joint
*/
const std::string& getName()const
{
return name;
}
/**
* Request the type of the joint.
*
* @return const reference to the type
*/
const JointType& getType() const
{
return type;
};
/**
* Request the stringified type of the joint.
*
* @return const string
*/
const std::string getTypeName() const
{
switch (type) {
case RotAxis:
return "RotAxis";
case TransAxis:
return "TransAxis";
case RotX:
return "RotX";
case RotY:
return "RotY";
case RotZ:
return "RotZ";
case TransX:
return "TransX";
case TransY:
return "TransY";
case TransZ:
return "TransZ";
case None:
return "None";
default:
return "None";
}
};
virtual ~Joint();
private:
std::string name;
Joint::JointType type;
double scale;
double offset;
double inertia;
double damping;
double stiffness;
// variables for RotAxis joint
Vector axis, origin;
mutable Frame joint_pose;
mutable double q_previous;
class joint_type_exception: public std::exception{
virtual const char* what() const throw(){
return "Joint Type excption";}
} joint_type_ex;
};
} // end of namespace KDL
#endif
|