Struct arcos_kdl::kinematic_arm::KinematicArm[][src]

pub struct KinematicArm { /* fields omitted */ }
Expand description

Implementation of kinematic arms

These are the subset of kinematic chains that are used as robotic
arms. With an improved API for ease of used compared to the one
we have for kinematic chains. It is different from the chain because
it has a shoulder segment (segment with no joint) at the beginning
and then N mobile segments. Also has a base transform that represents
the robotic body to which the arm is attached.

base_transform: Pose of the base of the shoulder
chain: The kinematic chain that describes the arm
forward_solver: Forward kinematics solver
forward_diff_solver: Forward Differential kinematics solver
inverse_diff_solver: Inverse differential kinematics solver
joint_limits: Mechanical joint limits (radians)
joint_speed_limits: max speed of each joint (radians/s)
weights: the weight of each joint for inverse kinematics
state: current state of each joint (radians)
speed: current speed of each joint (radians/s)\

Implementations

Default empty kinematic arm

Get how many joints the kinematic arm has

Get how many segments the kinematic arm has

Get the limits of each joint

Get the speed limits of each joint

Set the base pose transformation.
transform: A Frame holding the base transform to set

Set the base velocity.
twist: the twist of the base to set

Add a shoulder to the kinematic arm. This will remove the current
chain and add a new one with this shoulder
shoulder: a segment holding the shoulder

Add a shoulder to the kinematic arm. This will remove the current
chain and add a new one with this shoulder.
shoulder_tf: Frame holding the shoulder transform

Add a new segment to the description of the kinematic arm.
It will be added to the end of the current chain
segment: The new segment to add
limits: mechanical limits of the joint (radians)
speed_limits: speed limit of the joint (radians/s)\

Add a new joint by Type and transform. See ‘add_segment’ for more info
joint_type: type of joint
transform: transform of the segment
limits: mechanical limits of the joint (radians)
speed_limits: speed limit of the joint (radians/s)\

Set the weight ranges for each joint. The algorithm will use the highest
weight for each joint, but when it gets close to the limit, it will
switch to the minimum weight to avoid a collision (to the joint limit)
weights: Weight for normal operation of the arm
min_weights: Weight to use when the joint approaches its limit.

Set the weights of each joint. This tells the algorithm how much to move
each joint for IK. The weight is a floating value between 0 and 1, where
1 means free movement and 0 means to stay put.
weights: The weight for each movable joint\

Set how much to avoid singularities for inverse kinematics.
It is a scalar from 0 to 1 where
0 means low avoidance and high accuracy and 1 means high avoidance
and low accuracy.
lambda: singularity avoidance\

Configure the behaviour of the inverse kinematics differential
solver. By changing the epsilon and maximum iterations parameters.
Lower epsilon means more accuracy but slower execution. Higher
maxiter means higher robustness but slower executions.
epsilon: IK SVD solution threshold max_iter: IK SVD solver maximum iterations

Get the current joint speeds (radians/s)\

Get the current joint state (radians)\

Set the speeds of each joint.
joint_speeds: vector with the speed to set (radians/s). Must be the same
length as movable joints in the arm\

Set the state of each joint. If the joint approaches a limit, it will also handle the weights for the inverse kinematic solver.
joint_states: vector with the state to set (radians). Must be the same length as movable joints in the arm\

Get the end effector pose. Takes into consideration the pose of the base of the arm.

Get the end effector twist. Takes into consideration the pose and twist of the base of the arm

Get the end effector local pose, from the shoulder to the end effector.

Get the end effector local twist, from the shoulder to the

Move the base.\

Move the end effector a differential
twist: Required or commanded Twist
dt: time differential\

Move to the goal pose in a straight line from the current pose to the goal.

goal: the goal pose
speed: the speed at which the end effector should move
rot_speed: the speed at which the end effector should rotate
dt: time differential
timeout: time after which the goal is unreachable
translation_tolerance: allowed translational error
rotation_tolerance: allowed rotational error
returns final state if reachable\

Build the arm from a kinematic description.\

Return the description of the current arm

Trait Implementations

Returns a copy of the value. Read more

Performs copy-assignment from source. Read more

Formats the value using the given formatter. Read more

This method tests for self and other values to be equal, and is used by ==. Read more

This method tests for !=.

Auto Trait Implementations

Blanket Implementations

Gets the TypeId of self. Read more

Immutably borrows from an owned value. Read more

Mutably borrows from an owned value. Read more

Performs the conversion.

Performs the conversion.

Should always be Self

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more

Checks if self is actually part of its subset T (and can be converted to it).

Use with care! Same as self.to_subset but without any property checks. Always succeeds.

The inclusion map: converts self to the equivalent element of its superset.

The resulting type after obtaining ownership.

Creates owned data from borrowed data, usually by cloning. Read more

🔬 This is a nightly-only experimental API. (toowned_clone_into)

recently added

Uses borrowed data to replace owned data, usually by cloning. Read more

The type returned in the event of a conversion error.

Performs the conversion.

The type returned in the event of a conversion error.

Performs the conversion.