KrisLibrary
1.0.0
|
Class defining kinematics of a robot, and commonly used functions. More...
#include <RobotKinematics3D.h>
Public Member Functions | |
virtual std::string | LinkName (int i) const |
void | Initialize (int numLinks) |
Initializer: blank robot. | |
void | InitializeRigidObject () |
Initializer: rigid object. | |
void | Merge (const std::vector< RobotKinematics3D * > &robots) |
Initializer: merge some robots into one big robot. | |
void | Subset (const RobotKinematics3D &robot, const std::vector< int > &subset) |
Initializer: select a subset of the robot links as DOFs. | |
void | UpdateFrames () |
based on the values in q, update the frames T | |
void | UpdateSelectedFrames (int link, int root=-1) |
based on the values in q, update the frames of link T up to the root | |
void | UpdateConfig (const Config &q) |
sets the current config q and updates frames | |
bool | InJointLimits (const Config &q) const |
returns true if q is within joint limits | |
void | NormalizeAngles (Config &q) const |
normalizes angles in q to be within the range [qmin,qmax] | |
Real | GetTotalMass () const |
Vector3 | GetCOM () const |
Vector3 | GetCOM (const Config &q) |
Matrix3 | GetTotalInertia () const |
void | GetCOMJacobian (Matrix &Jc) const |
void | GetCOMHessian (Matrix &Hx, Matrix &Hy, Matrix &Hz) const |
void | GetGravityTorques (const Vector3 &g0, Vector &G) const |
Real | GetGravityPotentialEnergy (const Vector3 &g0, Real refHeight=Zero) const |
void | GetWorldPosition (const Vector3 &pi, int i, Vector3 &p) const |
in the following, pi is a point in the local frame of body i | |
const Matrix3 & | GetWorldRotation (int i) const |
void | GetWorldRotation_Moment (int i, Vector3 &m) const |
void | GetWorldVelocity (const Vector3 &pi, int i, const Vector &dq, Vector3 &dp) const |
gets the world velocity/angular velocity of pi, given dq/dt | |
void | GetWorldAngularVelocity (int i, const Vector &dq, Vector3 &omega) const |
bool | GetWorldRotationDeriv (int i, int j, Matrix3 &dR) const |
derivative of Ri w.r.t. qj | |
bool | GetWorldRotationDeriv_Moment (int i, int j, Vector3 &dm) const |
bool | GetWorldRotationDeriv_Moment (int i, int j, const Vector3 &m, Vector3 &dm) const |
same as above, but m s.t. Ri=e^[m] is specified | |
bool | GetJacobian (const Vector3 &pi, int i, int j, Vector3 &dw, Vector3 &dv) const |
gets the jacobian of pi w.r.t qj | |
bool | GetOrientationJacobian (int i, int j, Vector3 &dw) const |
bool | GetPositionJacobian (const Vector3 &pi, int i, int j, Vector3 &dv) const |
void | GetFullJacobian (const Vector3 &pi, int i, Matrix &J) const |
void | GetPositionJacobian (const Vector3 &pi, int i, Matrix &J) const |
rows 3-5 of the above | |
void | GetWrenchTorques (const Vector3 &torque, const Vector3 &force, int i, Vector &F) const |
for a wrench w=(torque,force) on link i, returns joint torques F = J^t w | |
void | AddWrenchTorques (const Vector3 &torque, const Vector3 &force, int i, Vector &F) const |
void | GetForceTorques (const Vector3 &f, const Vector3 &pi, int i, Vector &F) const |
for a force f at pi on link i, returns joint torques F = J^t f | |
void | AddForceTorques (const Vector3 &f, const Vector3 &pi, int i, Vector &F) const |
bool | GetJacobianDeriv (const Vector3 &pm, int m, int i, int j, Vector3 &ddtheta, Vector3 &ddp) const |
void | GetJacobianDeriv_Fast (const Vector3 &pm, int m, int i, int j, Vector3 &ddtheta, Vector3 &ddp) const |
assumes i,j<=m | |
void | GetJacobianDeriv (const Vector3 &pm, int m, Matrix *Htheta[3], Matrix *Hp[3]) const |
void | GetPositionHessian (const Vector3 &pm, int m, Matrix *Hp[3]) const |
void | GetDirectionalHessian (const Vector3 &pm, int m, const Vector3 &v, Matrix &Hpv) const |
Real | PointDistanceBound (const Vector3 &pi, int i, const Config &q1, const Config &q2) const |
Real | PointDistanceBound2 (const Vector3 &pi, int i, const Config &q1, const Config &q2) |
A closer upper bound than the previous. Overwrites robot's state. | |
Real | SphereDistanceBound (const Vector3 &ci, Real r, int i, const Config &q1, const Config &q2) |
Public Member Functions inherited from Chain | |
bool | HasValidOrdering () const |
bool | IsAncestor (int n, int p) const |
Returns true if p is an ancestor of n. | |
bool | IsDescendent (int n, int c) const |
Returns true if c is a descendant of n. | |
int | LCA (int a, int b) const |
Least common ancestor. | |
void | GetChildList (std::vector< std::vector< int > > &children) const |
Returns a vector where element i is a vectors of the children of link i. | |
void | GetAncestors (int k, std::vector< bool > &ancestors) const |
Returns a vector where element i is true if it is an ancestor of n. | |
void | GetDescendants (int k, std::vector< bool > &descendants) const |
Returns a vector where element i is true if it is an descendant of n. | |
Public Attributes | |
std::vector< RobotLink3D > | links |
Config | q |
current configuration | |
Vector | qMin |
Vector | qMax |
joint limits | |
Public Attributes inherited from Chain | |
std::vector< int > | parents |
Topologically sorted list of parents. | |
Additional Inherited Members | |
Public Types inherited from Chain | |
enum | { NoParent = -1 } |
Class defining kinematics of a robot, and commonly used functions.
Defines a robot's kinematic model as an articulated set of links. The Chain superclass defines each link's parents. Note: links must be defined in topologically sorted order (parents before children) for many algorithms to work.
The current configuration is given by a Vector q. The current link frames are updated when UpdateFrames() is called, and are stored in links[i].T_World.
Note that the kinematic model is often used for temporary storage (i.e. in planners, simulators, etc.) so you should count on the state being changed. If you need to store state, copy out the current configuration.
gets the jacobian matrix of pi w.r.t q row 0-2 are angular, 3-5 are translational
bool RobotKinematics3D::GetJacobianDeriv | ( | const Vector3 & | pm, |
int | m, | ||
int | i, | ||
int | j, | ||
Vector3 & | ddtheta, | ||
Vector3 & | ddp | ||
) | const |
In the following, the pseudo-hessian H[i,j] is d/dqj(dpm/dqi) for the points pm on link m (in local coordinates). It is a pseudo-hessian because the orientation components are not symmetric. The position components are a true hessian.
Referenced by GetJacobianDeriv_Fast().
Real RobotKinematics3D::PointDistanceBound | ( | const Vector3 & | pi, |
int | i, | ||
const Config & | q1, | ||
const Config & | q2 | ||
) | const |
Upper bounds the distance traveled by the point (attached to link i's frame) when moving from q1 to q2 (in a linear interpolation).
Real RobotKinematics3D::SphereDistanceBound | ( | const Vector3 & | ci, |
Real | r, | ||
int | i, | ||
const Config & | q1, | ||
const Config & | q2 | ||
) |
Upper bounds the distance traveled by a sphere attached to the local frame of i, centered at ci with radius r, when moving from q1 to q2 (in a linear interpolation). Uses algorithm 2.