Skeleton models¤
As subclasses ultimately of AbstractDynamicalSystem
, skeleton models in Feedbax define the continuous skeletal dynamics with a vector_field
method, which returns the time derivatives of the skeletal state.
feedbax.mechanics.skeleton.PointMass
(AbstractSkeleton[CartesianState])
¤
A point with mass but no spatial extent, that obeys Newton's laws of motion.
Attributes:
Name | Type | Description |
---|---|---|
A |
Array
|
The state evolution matrix according to Newton's first law of motion. |
B |
Array
|
The control matrix according to Newton's second law. |
vector_field
(
t
: Scalar
,
state
: CartesianState
,
input
: Float[Array, input]
)
->
CartesianState
¤
vector_field
(
t
: Scalar
,
state
: CartesianState
,
input
: Float[Array, input]
)
->
CartesianState
Returns time derivatives of the system's states.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
t |
Scalar
|
The current simulation time. (Unused.) |
required |
state |
CartesianState
|
The state of the point mass. |
required |
input |
Float[Array, input]
|
The input force on the point mass. |
required |
init
(
*,
key
: PRNGKeyArray
)
->
CartesianState
¤
init
(
*,
key
: PRNGKeyArray
)
->
CartesianState
Return a default state for the point mass.
effector
(
config_state
: CartesianState
)
->
CartesianState
¤
effector
(
config_state
: CartesianState
)
->
CartesianState
Return the effector state given the configuration state.
For a point mass, these are identical. However, we make sure to
return zero force
to avoid positive feedback loops as effector
forces are converted back to system forces by Mechanics
on the
next time step.
forward_kinematics
(
state
: CartesianState
)
->
CartesianState
¤
forward_kinematics
(
state
: CartesianState
)
->
CartesianState
Trivially, returns the Cartesian state of the point mass itself.
inverse_kinematics
(
effector_state
: CartesianState
)
->
CartesianState
¤
inverse_kinematics
(
effector_state
: CartesianState
)
->
CartesianState
Trivially, returns the Cartesian state of the point mass itself.
update_state_given_effector_force
(
effector_force
: Array
,
system_state
: CartesianState
,
*,
key
: Optional[PRNGKeyArray] = None
)
->
CartesianState
¤
update_state_given_effector_force
(
effector_force
: Array
,
system_state
: CartesianState
,
*,
key
: Optional[PRNGKeyArray] = None
)
->
CartesianState
Updates the force on the point mass.
Effector forces are equal to configuration forces for a point mass, so this just inserts the effector force into the state directly. This method exists because for more complex skeletons, the conversion is not trivial.
feedbax.mechanics.skeleton.TwoLinkArmState
(AbstractSkeletonState)
¤
The configuration state of a 2D arm with two rotational joints.
Attributes:
Name | Type | Description |
---|---|---|
angle |
Float[Array, '... links=2']
|
The joint angles. |
d_angle |
Float[Array, '... links=2']
|
The angular velocities. |
torque |
Float[Array, '... links=2']
|
The torques on the joints. |
feedbax.mechanics.skeleton.TwoLinkArm
(AbstractSkeleton[TwoLinkArmState])
¤
Model of a 2D arm with two straight rigid segments, and two rotational joints.
Attributes:
Name | Type | Description |
---|---|---|
l |
Float[Array, 'links=2']
|
The lengths of the arm segments. Units: \([\mathrm{L}]\). |
m |
Float[Array, 'links=2']
|
The masses of the segments. Units: \([\mathrm{M}]\). |
I |
Float[Array, 'links=2']
|
The moments of inertia of the segments. Units: \([\mathrm{M}\cdot \mathrm{L}^2]\). |
s |
Float[Array, 'links=2']
|
The distance from the joint center to the segment center of mass for each segment. Units: \([\mathrm{L}]\). |
B |
Float[Array, '2 2']
|
The joint friction matrix. Units: \([\mathrm{M}\cdot \mathrm{L}^2\cdot \mathrm{T}^{-1}]\). |
bounds: StateBounds[TwoLinkArmState]
property
¤
Suggested bounds on the arm state.
Source
Joint angle limits adopted from MotorNet.
vector_field
(
t
: Scalar
,
state
: TwoLinkArmState
,
input
: Array
)
->
TwoLinkArmState
¤
vector_field
(
t
: Scalar
,
state
: TwoLinkArmState
,
input
: Array
)
->
TwoLinkArmState
Return the time derivatives of the arm's configuration state.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
t |
Scalar
|
The time. Not used. |
required |
state |
TwoLinkArmState
|
The current state of the arm. |
required |
input |
Array
|
The torques on the joints. |
required |
init
(
*,
key
: Optional[PRNGKeyArray] = None
)
->
TwoLinkArmState
¤
init
(
*,
key
: Optional[PRNGKeyArray] = None
)
->
TwoLinkArmState
Return a default state for the arm.
effector
(
state
: TwoLinkArmState
)
->
CartesianState
¤
effector
(
state
: TwoLinkArmState
)
->
CartesianState
Return the Cartesian state of the endpoint of the arm.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
state |
TwoLinkArmState
|
The configuration state of the arm. |
required |
forward_kinematics
(
state
: TwoLinkArmState
)
->
CartesianState
¤
forward_kinematics
(
state
: TwoLinkArmState
)
->
CartesianState
Return the Cartesian state of the joints and end effector, given the arm's configuration state.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
state |
TwoLinkArmState
|
The configuration state of the arm. |
required |
inverse_kinematics
(
effector_state
: CartesianState
)
->
TwoLinkArmState
¤
inverse_kinematics
(
effector_state
: CartesianState
)
->
TwoLinkArmState
Return the configuration state of the arm, given the Cartesian state of the end effector.
There are two possible solutions to the inverse kinematics problem, for a two-link arm. This method returns the "elbow down" or "righty" solution.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
effector_state |
CartesianState
|
The state of the end effector. |
required |
update_state_given_effector_force
(
effector_force
: Array
,
state
: TwoLinkArmState
,
*,
key
: Optional[PRNGKeyArray] = None
)
->
TwoLinkArmState
¤
update_state_given_effector_force
(
effector_force
: Array
,
state
: TwoLinkArmState
,
*,
key
: Optional[PRNGKeyArray] = None
)
->
TwoLinkArmState
Adds torques implied by a force on the end effector, to a configuration state of the arm.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
effector_force |
Array
|
The force on the end effector. |
required |
state |
TwoLinkArmState
|
The configuration state of the arm to which to add the inferred torques. |
required |
key |
Optional[PRNGKeyArray]
|
Unused. To satisfy the signature expected by
|
None
|
effector_jac
(
angle
: Float[Array, 'links=2']
)
->
Float[Array, 'ndim=2 links=2']
¤
effector_jac
(
angle
: Float[Array, 'links=2']
)
->
Float[Array, 'ndim=2 links=2']
Return the Jacobian of end effector position with respect to joint angles.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
angle |
Float[Array, 'links=2']
|
The joint angles. |
required |
workspace_test
(
workspace
: Float[Array, 'bounds=2 xy=2']
)
->
bool
¤
workspace_test
(
workspace
: Float[Array, 'bounds=2 xy=2']
)
->
bool
Tests whether a rectangular workspace is reachable by the arm.
Assumes the arm's joint angles are not bounded.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
workspace |
Float[Array, 'bounds=2 xy=2']
|
The bounds of the workspace to test. |
required |
Abstract base classes¤
feedbax.mechanics.skeleton.AbstractSkeleton
(AbstractDynamicalSystem[StateT])
¤
Base class for models of skeletal dynamics.
vector_field
(
t
: Scalar
,
state
: StateT
,
input
: Array
)
->
StateT
abstractmethod
¤
vector_field
(
t
: Scalar
,
state
: StateT
,
input
: Array
)
->
StateT
Return the time derivative of the state of the skeleton.
init
(
*,
key
: PRNGKeyArray
)
->
StateT
abstractmethod
¤
init
(
*,
key
: PRNGKeyArray
)
->
StateT
Return a default state for the skeleton.
effector
(
state
: StateT
)
->
CartesianState
abstractmethod
¤
effector
(
state
: StateT
)
->
CartesianState
Return the Cartesian state of the end effector.
forward_kinematics
(
state
: StateT
)
->
CartesianState
abstractmethod
¤
forward_kinematics
(
state
: StateT
)
->
CartesianState
Return the Cartesian state of the joints and end effector, given the configuration of the skeleton.
inverse_kinematics
(
effector_state
: CartesianState
)
->
StateT
abstractmethod
¤
inverse_kinematics
(
effector_state
: CartesianState
)
->
StateT
Return the configuration of the skeleton given the Cartesian state of the end effector.
update_state_given_effector_force
(
effector_force
: Array
,
state
: StateT
,
*,
key
: Optional[PRNGKeyArray] = None
)
->
StateT
abstractmethod
¤
update_state_given_effector_force
(
effector_force
: Array
,
state
: StateT
,
*,
key
: Optional[PRNGKeyArray] = None
)
->
StateT
Update the state of the skeleton given a force on the end effector.