|
Robotics Library
0.7.0
|
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);
68 ::std::size_t
getDof()
const;
78 const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>&
getPositionUnits()
const;
82 const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>&
getTorqueUnits()
const;
86 const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>&
getSpeedUnits()
const;
90 const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>&
getVelocityUnits()
const;
126 ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>
qUnits;
130 ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>
qdUnits;
134 ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>
qddUnits;
140 ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>
speedUnits;
144 ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>
tauUnits;
162 #endif // RL_MDL_JOINT_H
::rl::math::Matrix S
Definition: Joint.h:136
::Eigen::Matrix< Real, ::Eigen::Dynamic, ::Eigen::Dynamic > Matrix
Definition: Matrix.h:42
::rl::math::Vector qdd
Definition: Joint.h:132
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > tauUnits
Definition: Joint.h:144
virtual ::rl::math::Real transformedDistance(const ::rl::math::Vector &q1, const ::rl::math::Vector &q2) const
Definition: Joint.cpp:351
::rl::math::Vector max
Definition: Joint.h:118
::rl::math::MotionVector v
Definition: Joint.h:150
const ::rl::math::Vector & getVelocity() const
Definition: Joint.cpp:273
const ::rl::math::Vector & getAcceleration() const
Definition: Joint.cpp:201
::Eigen::Ref< const Vector > ConstVectorRef
Definition: Vector.h:74
::rl::math::Vector min
Definition: Joint.h:120
::rl::math::Vector q
Definition: Joint.h:124
virtual void normalize(::rl::math::Vector &q) const
Definition: Joint.cpp:315
Joint(const ::std::size_t &dofPosition, const ::std::size_t &dofVelocity)
Definition: Joint.cpp:34
::rl::math::Vector qd
Definition: Joint.h:128
virtual void step(const ::rl::math::Vector &q1, const ::rl::math::Vector &qdot, ::rl::math::Vector &q2) const
Definition: Joint.cpp:344
const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > & getTorqueUnits() const
Definition: Joint.cpp:255
void forwardDynamics1()
Definition: Joint.cpp:123
::rl::math::Vector tau
Definition: Joint.h:142
void forwardVelocity()
Definition: Joint.cpp:166
void forwardDynamics3()
Definition: Joint.cpp:152
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > qUnits
Definition: Joint.h:126
void setVelocity(const ::rl::math::Vector &qd)
Definition: Joint.cpp:335
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > speedUnits
Definition: Joint.h:140
::Eigen::Matrix< Real, ::Eigen::Dynamic, 1 > Vector
Definition: Vector.h:42
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
virtual ::rl::math::Vector generatePositionGaussian(const ::rl::math::ConstVectorRef &rand, const ::rl::math::ConstVectorRef &mean, const ::rl::math::ConstVectorRef &sigma) const
Definition: Joint.cpp:173
const ::rl::math::Vector & getSpeed() const
Definition: Joint.cpp:261
::rl::math::MotionVector a
Definition: Joint.h:112
::rl::math::Vector speed
Definition: Joint.h:138
virtual ::rl::math::Vector generatePositionUniform(const ::rl::math::ConstVectorRef &rand) const
Definition: Joint.cpp:188
const ::rl::math::Vector & getPosition() const
Definition: Joint.cpp:237
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > qdUnits
Definition: Joint.h:130
virtual bool isValid(const ::rl::math::Vector &q) const
Definition: Joint.cpp:301
void setAcceleration(const ::rl::math::Vector &qdd)
Definition: Joint.cpp:320
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:285
const ::rl::math::Vector & getMinimum() const
Definition: Joint.cpp:231
::rl::math::Vector offset
Definition: Joint.h:122
::rl::math::Vector u
Definition: Joint.h:146
void setTorque(const ::rl::math::Vector &tau)
Definition: Joint.cpp:329
void forwardAcceleration()
Definition: Joint.cpp:116
::Eigen::Matrix< bool, ::Eigen::Dynamic, 1 > wraparound
Definition: Joint.h:152
::std::size_t getDof() const
Definition: Joint.cpp:213
::std::size_t getDofPosition() const
Definition: Joint.cpp:219
virtual ~Joint()
Definition: Joint.cpp:75
::rl::math::Matrix D
Definition: Joint.h:116
::rl::math::Matrix U
Definition: Joint.h:148
const ::rl::math::Vector & getTorque() const
Definition: Joint.cpp:249
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:42
Motion vector.
Definition: MotionVector.h:45
const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > & getVelocityUnits() const
Definition: Joint.cpp:279
::rl::math::MotionVector c
Definition: Joint.h:114
const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > & getSpeedUnits() const
Definition: Joint.cpp:267
const ::rl::math::Vector & getMaximum() const
Definition: Joint.cpp:225
const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > & getAccelerationUnits() const
Definition: Joint.cpp:207
const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > & getPositionUnits() const
Definition: Joint.cpp:243
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > qddUnits
Definition: Joint.h:134
void inverseForce()
Definition: Joint.cpp:291
Robotics Library.
Definition: AnalogInput.cpp:30