|
Robotics Library
0.6.2
|
Go to the documentation of this file.
27 #ifndef _RL_MDL_JOINT_H_
28 #define _RL_MDL_JOINT_H_
42 Joint(const ::std::size_t& dofPosition, const ::std::size_t& dofVelocity);
64 ::std::size_t
getDof()
const;
74 const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 >&
getPositionUnits()
const;
78 const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 >&
getTorqueUnits()
const;
82 const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 >&
getSpeedUnits()
const;
86 const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 >&
getVelocityUnits()
const;
120 ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 >
qUnits;
124 ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 >
qdUnits;
128 ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 >
qddUnits;
134 ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 >
speedUnits;
138 ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 >
tauUnits;
156 #endif // _RL_MDL_JOINT_H_
::rl::math::Matrix S
Definition: Joint.h:130
::rl::math::Vector qdd
Definition: Joint.h:126
virtual ::rl::math::Real transformedDistance(const ::rl::math::Vector &q1, const ::rl::math::Vector &q2) const
Definition: Joint.cpp:318
::rl::math::Vector max
Definition: Joint.h:112
::rl::math::MotionVector v
Definition: Joint.h:144
const ::rl::math::Vector & getVelocity() const
Definition: Joint.cpp:245
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > speedUnits
Definition: Joint.h:134
const ::rl::math::Vector & getAcceleration() const
Definition: Joint.cpp:173
::rl::math::Vector min
Definition: Joint.h:114
::rl::math::Vector q
Definition: Joint.h:118
Joint(const ::std::size_t &dofPosition, const ::std::size_t &dofVelocity)
Definition: Joint.cpp:34
::Eigen::Matrix< bool, ::Eigen::Dynamic, 1 > wraparound
Definition: Joint.h:146
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > tauUnits
Definition: Joint.h:138
::rl::math::Vector qd
Definition: Joint.h:122
virtual void step(const ::rl::math::Vector &q1, const ::rl::math::Vector &qdot, ::rl::math::Vector &q2) const
Definition: Joint.cpp:311
const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > & getTorqueUnits() const
Definition: Joint.cpp:227
void forwardDynamics1()
Definition: Joint.cpp:123
::rl::math::Vector tau
Definition: Joint.h:136
void forwardVelocity()
Definition: Joint.cpp:166
void forwardDynamics3()
Definition: Joint.cpp:152
void setVelocity(const ::rl::math::Vector &qd)
Definition: Joint.cpp:302
virtual ::rl::math::Real distance(const ::rl::math::Vector &q1, const ::rl::math::Vector &q2) const
Definition: Joint.cpp:110
void forwardDynamics2()
Definition: Joint.cpp:131
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > qddUnits
Definition: Joint.h:128
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > qUnits
Definition: Joint.h:120
const ::rl::math::Vector & getSpeed() const
Definition: Joint.cpp:233
::rl::math::MotionVector a
Definition: Joint.h:106
::rl::math::Vector speed
Definition: Joint.h:132
::Eigen::Matrix< Real, ::Eigen::Dynamic, ::Eigen::Dynamic > Matrix
Definition: Matrix.h:41
const ::rl::math::Vector & getPosition() const
Definition: Joint.cpp:209
virtual bool isValid(const ::rl::math::Vector &q) const
Definition: Joint.cpp:273
void setAcceleration(const ::rl::math::Vector &qdd)
Definition: Joint.cpp:287
virtual void interpolate(const ::rl::math::Vector &q1, const ::rl::math::Vector &q2, const ::rl::math::Real &alpha, ::rl::math::Vector &q) const
Definition: Joint.cpp:257
const ::rl::math::Vector & getMinimum() const
Definition: Joint.cpp:203
::rl::math::Vector offset
Definition: Joint.h:116
::rl::math::Vector u
Definition: Joint.h:140
void setTorque(const ::rl::math::Vector &tau)
Definition: Joint.cpp:296
void forwardAcceleration()
Definition: Joint.cpp:116
::std::size_t getDof() const
Definition: Joint.cpp:185
::std::size_t getDofPosition() const
Definition: Joint.cpp:191
virtual ~Joint()
Definition: Joint.cpp:75
::Eigen::Matrix< Real, ::Eigen::Dynamic, 1 > Vector
Definition: Vector.h:41
::rl::math::Matrix D
Definition: Joint.h:110
::rl::math::Matrix U
Definition: Joint.h:142
const ::rl::math::Vector & getTorque() const
Definition: Joint.cpp:221
virtual void setPosition(const ::rl::math::Vector &q)=0
virtual void clip(::rl::math::Vector &q) const
Definition: Joint.cpp:80
double Real
Definition: Real.h:34
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > qdUnits
Definition: Joint.h:124
Definition: MotionVector.h:42
const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > & getVelocityUnits() const
Definition: Joint.cpp:251
::rl::math::MotionVector c
Definition: Joint.h:108
const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > & getSpeedUnits() const
Definition: Joint.cpp:239
const ::rl::math::Vector & getMaximum() const
Definition: Joint.cpp:197
const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > & getAccelerationUnits() const
Definition: Joint.cpp:179
const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > & getPositionUnits() const
Definition: Joint.cpp:215
void inverseForce()
Definition: Joint.cpp:263