Skip to content

Commit

Permalink
Added doxygen fixes from svn commit 3590 to KDL
Browse files Browse the repository at this point in the history
  • Loading branch information
yorikvanhavre committed Oct 14, 2015
1 parent 9f4e7c4 commit 1908e85
Show file tree
Hide file tree
Showing 26 changed files with 89 additions and 64 deletions.
2 changes: 1 addition & 1 deletion src/Mod/Robot/App/kdl_cp/articulatedbodyinertia.cpp
Expand Up @@ -41,7 +41,7 @@ namespace KDL{
*this = RigidBodyInertia(m,c,Ic);
}

ArticulatedBodyInertia::ArticulatedBodyInertia(const Matrix3d& M, const Matrix3d& H, const Matrix3d& I)
ArticulatedBodyInertia::ArticulatedBodyInertia(const Eigen::Matrix3d& M, const Eigen::Matrix3d& H, const Eigen::Matrix3d& I)
{
this->M=M;
this->I=I;
Expand Down
5 changes: 4 additions & 1 deletion src/Mod/Robot/App/kdl_cp/chainfksolver.hpp
Expand Up @@ -48,6 +48,7 @@ namespace KDL {
*
* @param q_in input joint coordinates
* @param p_out reference to output cartesian pose
* @param segmentNr default to -1
*
* @return if < 0 something went wrong
*/
Expand All @@ -69,6 +70,7 @@ namespace KDL {
*
* @param q_in input joint coordinates (position and velocity)
* @param out output cartesian coordinates (position and velocity)
* @param segmentNr default to -1
*
* @return if < 0 something went wrong
*/
Expand All @@ -92,8 +94,9 @@ namespace KDL {
*
* @param q_in input joint coordinates (position, velocity and
* acceleration
@param out output cartesian coordinates (position, velocity
* @param out output cartesian coordinates (position, velocity
* and acceleration
* @param segmentNr default to -1
*
* @return if < 0 something went wrong
*/
Expand Down
7 changes: 4 additions & 3 deletions src/Mod/Robot/App/kdl_cp/chainidsolver.hpp
Expand Up @@ -41,14 +41,15 @@ namespace KDL
{
public:
/**
* Calculate inverse dynamics, from joint positions, velocity, acceleration, external forces
* Calculate inverse dynamics, from joint positions,
* velocity, acceleration, external forces
* to joint torques/forces.
*
* @param q input joint positions
* @param q_dot input joint velocities
* @param q_dotdot input joint accelerations
*
* @param torque output joint torques
* @param f_ext external forces
* @param torques output joint torques
*
* @return if < 0 something went wrong
*/
Expand Down
4 changes: 0 additions & 4 deletions src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv_givens.hpp
Expand Up @@ -29,10 +29,6 @@ namespace KDL
*
* @param chain the chain to calculate the inverse velocity
* kinematics for
* @param eps if a singular value is below this value, its
* inverse is set to zero, default: 0.00001
* @param maxiter maximum iterations for the svd calculation,
* default: 150
*
*/
explicit ChainIkSolverVel_pinv_givens(const Chain& chain);
Expand Down
4 changes: 2 additions & 2 deletions src/Mod/Robot/App/kdl_cp/chainiksolvervel_wdls.cpp
Expand Up @@ -54,11 +54,11 @@ namespace KDL
{
}

void ChainIkSolverVel_wdls::setWeightJS(const MatrixXd& Mq){
void ChainIkSolverVel_wdls::setWeightJS(const Eigen::MatrixXd& Mq){
weight_js = Mq;
}

void ChainIkSolverVel_wdls::setWeightTS(const MatrixXd& Mx){
void ChainIkSolverVel_wdls::setWeightTS(const Eigen::MatrixXd& Mx){
weight_ts = Mx;
}

Expand Down
10 changes: 6 additions & 4 deletions src/Mod/Robot/App/kdl_cp/chainiksolvervel_wdls.hpp
Expand Up @@ -108,8 +108,9 @@ namespace KDL
/**
* Set the joint space weighting matrix
*
* @param weight_js joint space weighting symetric matrix,
* default : identity. M_q : This matrix being used as a
* weight_js joint space weighting symetric matrix,
* default : identity.
* @param Mq : This matrix being used as a
* weight for the norm of the joint space speed it HAS TO BE
* symmetric and positive definite. We can actually deal with
* matrices containing a symmetric and positive definite block
Expand All @@ -132,8 +133,9 @@ namespace KDL
/**
* Set the task space weighting matrix
*
* @param weight_ts task space weighting symetric matrix,
* default: identity M_x : This matrix being used as a weight
* weight_ts task space weighting symetric matrix,
* default: identity
* @param Mx : This matrix being used as a weight
* for the norm of the error (in terms of task space speed) it
* HAS TO BE symmetric and positive definite. We can actually
* deal with matrices containing a symmetric and positive
Expand Down
4 changes: 2 additions & 2 deletions src/Mod/Robot/App/kdl_cp/frameacc.hpp
Expand Up @@ -260,14 +260,14 @@ class TwistAcc




}


#ifdef KDL_INLINE
#include "frameacc.inl"
#endif

}




Expand Down
3 changes: 2 additions & 1 deletion src/Mod/Robot/App/kdl_cp/frameacc.inl
Expand Up @@ -17,7 +17,7 @@
****************************************************************************/



namespace KDL {

/////////////////// VectorAcc /////////////////////////////////////

Expand Down Expand Up @@ -596,3 +596,4 @@ bool Equal(const TwistAcc& a,const Twist& b,double eps) {
Equal(a.vel,b.vel,eps) );
}

}
9 changes: 4 additions & 5 deletions src/Mod/Robot/App/kdl_cp/frames.hpp
Expand Up @@ -639,9 +639,9 @@ class Frame {
//! @return the identity transformation Frame(Rotation::Identity(),Vector::Zero()).
inline static Frame Identity();

//! The twist <t_this> is expressed wrt the current
//! The twist \<t_this\> is expressed wrt the current
//! frame. This frame is integrated into an updated frame with
//! <samplefrequency>. Very simple first order integration rule.
//! \<samplefrequency\>. Very simple first order integration rule.
inline void Integrate(const Twist& t_this,double frequency);

/*
Expand Down Expand Up @@ -1249,6 +1249,8 @@ IMETHOD Twist addDelta(const Twist& a,const Twist&da,double dt=1);
*/
IMETHOD Wrench addDelta(const Wrench& a,const Wrench&da,double dt=1);

} // namespace KDL

#ifdef KDL_INLINE
// #include "vector.inl"
// #include "wrench.inl"
Expand All @@ -1263,7 +1265,4 @@ IMETHOD Wrench addDelta(const Wrench& a,const Wrench&da,double dt=1);



}


#endif
3 changes: 2 additions & 1 deletion src/Mod/Robot/App/kdl_cp/frames.inl
Expand Up @@ -31,7 +31,7 @@
*
*/


namespace KDL {

IMETHOD Vector::Vector(const Vector & arg)
{
Expand Down Expand Up @@ -1334,3 +1334,4 @@ IMETHOD bool operator!=(const Vector2& a,const Vector2& b) {
return !operator==(a,b);
}

} // namespace KDL
6 changes: 3 additions & 3 deletions src/Mod/Robot/App/kdl_cp/framevel.hpp
Expand Up @@ -52,7 +52,7 @@ IMETHOD void posrandom(doubleVel& F) {
posrandom(F.grad);
}

}
} //namespace KDL

template <>
struct Traits<KDL::doubleVel> {
Expand Down Expand Up @@ -383,12 +383,12 @@ IMETHOD void posrandom(FrameVel& F) {
posrandom(F.p);
}

} // namespace KDL

#ifdef KDL_INLINE
#include "framevel.inl"
#endif

} // namespace

#endif


Expand Down
3 changes: 3 additions & 0 deletions src/Mod/Robot/App/kdl_cp/framevel.inl
Expand Up @@ -16,6 +16,7 @@
* $Name: $
****************************************************************************/

namespace KDL {

// Methods and operators related to FrameVelVel
// They all delegate most of the work to RotationVelVel and VectorVelVel
Expand Down Expand Up @@ -532,3 +533,5 @@ Twist TwistVel::GetTwist() const {
Twist TwistVel::GetTwistDot() const {
return Twist(vel.v,rot.v);
}

} // namespace KDL
12 changes: 12 additions & 0 deletions src/Mod/Robot/App/kdl_cp/jntarray.hpp
Expand Up @@ -139,6 +139,18 @@ class MyTask : public RTT::TaskContext
friend void Subtract(const JntArray& src1,const JntArray& src2,JntArray& dest);
friend void Multiply(const JntArray& src,const double& factor,JntArray& dest);
friend void Divide(const JntArray& src,const double& factor,JntArray& dest);
/**
* Function to multiply a KDL::Jacobian with a KDL::JntArray
* to get a KDL::Twist, it should not be used to calculate the
* forward velocity kinematics, the solver classes are built
* for this purpose.
* J*q = t
*
* @param jac J
* @param src q
* @param dest t
* @post dest == (KDL::Twist::)Zero() if 0 == src.rows() (ie src is empty)
*/
friend void MultiplyJacobian(const Jacobian& jac, const JntArray& src, Twist& dest);
friend void SetToZero(JntArray& array);
friend bool Equal(const JntArray& src1,const JntArray& src2,double eps);
Expand Down
12 changes: 6 additions & 6 deletions src/Mod/Robot/App/kdl_cp/jntspaceinertiamatrix.hpp
Expand Up @@ -63,7 +63,7 @@ class MyTask : public RTT::TaskContext
** use j here
}
};
/endcode
\endcode
*/

Expand Down Expand Up @@ -199,19 +199,19 @@ class MyTask : public RTT::TaskContext
* for this purpose.
* J*q = t
*
* @param jac J
* @param src q
* @param dest t
* @param src J: Inertia Matrix (6x6)
* @param vec q: Jacobian (6x1)
* @param dest t: Twist (6x1)
* @post dest==Twist::Zero() if 0==src.rows() (ie src is empty)
*/
void Multiply(const JntSpaceInertiaMatrix& src, const JntArray& vec, JntArray& dest);

/**
* Function to set all the values of the array to 0
*
* @param array
* @param mat
*/
void SetToZero(JntSpaceInertiaMatrix& matrix);
void SetToZero(JntSpaceInertiaMatrix& mat);

/**
* Function to check if two matrices are the same with a
Expand Down
30 changes: 16 additions & 14 deletions src/Mod/Robot/App/kdl_cp/joint.hpp
Expand Up @@ -80,31 +80,33 @@ namespace KDL {
* 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
* @param _origin the origin of the joint
* @param _axis the axis of the joint
* @param type type of the joint
* @param _scale scale between joint input and actual geometric
* movement, default: 1
* @param offset offset between joint input and actual
* @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,
* @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
* @param _origin the origin of the joint
* @param _axis the axis of the joint
* @param type type of the joint
* @param _scale scale between joint input and actual geometric
* movement, default: 1
* @param offset offset between joint input and actual
* @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,
* @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,
Expand Down
6 changes: 4 additions & 2 deletions src/Mod/Robot/App/kdl_cp/kdl.hpp
Expand Up @@ -21,7 +21,8 @@
// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA

/**
* \mainpage KDL
* \defgroup KDL Kinematics and Dynamics Library
* \ingroup ROBOT
*
* This is the API reference of the
* <a href="http://www.orocos.org/kdl">Kinematics and Dynamics
Expand All @@ -32,7 +33,6 @@
* - \subpage geomprim
* - \ref KinematicFamily : functionality to build kinematic chains and access their kinematic and dynamic properties, such as e.g. Forward and Inverse kinematics and dynamics.
* - \ref Motion : functionality to specify motion trajectories of frames and kinematic chains, such as e.g. Trapezoidal Velocity profiles.
* - \ref KDLTK : the interface code to integrate KDL into the Orocos <a href="http://www.orocos.org/rtt/">Real-Time Toolkit</a> (RTT).
*
*
**/
Expand Down Expand Up @@ -125,5 +125,7 @@
* Typically we use the standard S.I. units: N, m, sec.
*
*/

/* This code doesn't seems to be integrated with freecad - \ref KDLTK : the interface code to integrate KDL into the Orocos <a href="http://www.orocos.org/rtt/">Real-Time Toolkit</a> (RTT). */


1 change: 1 addition & 0 deletions src/Mod/Robot/App/kdl_cp/kinfam.hpp
Expand Up @@ -21,6 +21,7 @@

/**
* @defgroup KinematicFamily Kinematic Families
* \ingroup KDL
* @brief All classes to support kinematic families.
*
* The Kinematic Families classes range from the basic building blocks
Expand Down
1 change: 1 addition & 0 deletions src/Mod/Robot/App/kdl_cp/motion.hpp
Expand Up @@ -21,6 +21,7 @@

/**
* @defgroup Motion Motion
* \ingroup KDL
* @brief All classes related to the non-instantaneous motion of rigid
* bodies and kinematic structures, e.g., path and trajecory definitions
* and their building blocks.
Expand Down
2 changes: 1 addition & 1 deletion src/Mod/Robot/App/kdl_cp/rotational_interpolation.hpp
Expand Up @@ -105,7 +105,7 @@ class RotationalInterpolation
static RotationalInterpolation* Read(std::istream& is);

/**
* virtual constructor, construction by copying ..
* virtual constructor, construction by copying.
*/
virtual RotationalInterpolation* Clone() const = 0;

Expand Down
4 changes: 2 additions & 2 deletions src/Mod/Robot/App/kdl_cp/segment.hpp
Expand Up @@ -60,7 +60,7 @@ namespace KDL {
* Joint(Joint::None)
* @param f_tip frame from the end of the joint to the tip of
* the segment, default: Frame::Identity()
* @param M rigid body inertia of the segment, default: Inertia::Zero()
* @param I rigid body inertia of the segment, default: Inertia::Zero()
*/
explicit Segment(const std::string& name, const Joint& joint=Joint(Joint::None), const Frame& f_tip=Frame::Identity(),const RigidBodyInertia& I = RigidBodyInertia::Zero());
/**
Expand All @@ -70,7 +70,7 @@ namespace KDL {
* Joint(Joint::None)
* @param f_tip frame from the end of the joint to the tip of
* the segment, default: Frame::Identity()
* @param M rigid body inertia of the segment, default: Inertia::Zero()
* @param I rigid body inertia of the segment, default: Inertia::Zero()
*/
explicit Segment(const Joint& joint=Joint(Joint::None), const Frame& f_tip=Frame::Identity(),const RigidBodyInertia& I = RigidBodyInertia::Zero());
Segment(const Segment& in);
Expand Down

0 comments on commit 1908e85

Please sign in to comment.