-
Notifications
You must be signed in to change notification settings - Fork 454
Link frame and joint definitions
The ERobot
is a general way to represent a rigid-body tree that can be a single serial-link chain or a branched mechanism.
Every link in the model has:
- a parent, except the root link
- zero, one or more children
- has a link coordinate frame in which inertial properties such as centre-of-mass and inertia are defined
This is shown diagrammatically below
where everything in red is a property (attribute) of link k, and everything in blue is a property of its parent link.
We borrow Featherstone's notation where the function is the parent of link k.
A robot joint connects two links. It connects coordinate frames on each side of the joint: the parent-side one expressed in the parent link's coordinate frame, and the child-side one is the child link's link coordinate frame.
is a constant transform, with respect to the parent frame, that describes the location of the parent-side of the joint. It is a property of the child link, since the parent link may have multiple children.
Frame can be expressed with respect to frame using an elementary-transform sequence (ETS). It comprises zero or more constant transforms and only one variable transform. It is parsed and processed at ELink
construction time and is accessed via attributes:
-
v
is a variable elementary transform representing the joint.v.eval(q)
is anSE3
object representing the joint transform . -
Ts
is anSE3
object, possibly identity, from precomputing the constant part of the ETS -
A(q)
is anSE3
object representing
With respect to Featherstone's notation.
- Frequently asked questions (FAQ)
- Documentation Style Guide
- Typing Style Guide
- Background
- Key concepts
- Introduction to robot and link classes
- Working with Jupyter
- Working from the command line
- What about Simulink?
- How to contribute
- Common Issues
- Contributors