pub struct Jacobian { /* private fields */ }
Expand description
This structure holds Jacobian matrix and provides methods to extract velocity and torgue information from it.
This package provides support for the Jacobian matrix.
The Jacobian matrix, as described here, represents the relationship between the joint velocities and the end-effector velocities:
| ∂vx/∂θ₁ ∂vx/∂θ₂ ∂vx/∂θ₃ ∂vx/∂θ₄ ∂vx/∂θ₅ ∂vx/∂θ₆ |
| ∂vy/∂θ₁ ∂vy/∂θ₂ ∂vy/∂θ₃ ∂vy/∂θ₄ ∂vy/∂θ₅ ∂vy/∂θ₆ |
| ∂vz/∂θ₁ ∂vz/∂θ₂ ∂vz/∂θ₃ ∂vz/∂θ₄ ∂vz/∂θ₅ ∂vz/∂θ₆ |
| ∂ωx/∂θ₁ ∂ωx/∂θ₂ ∂ωx/∂θ₃ ∂ωx/∂θ₄ ∂ωx/∂θ₅ ∂ωx/∂θ₆ |
| ∂ωy/∂θ₁ ∂ωy/∂θ₂ ∂ωy/∂θ₃ ∂ωy/∂θ₄ ∂ωy/∂θ₅ ∂ωy/∂θ₆ |
| ∂ωz/∂θ₁ ∂ωz/∂θ₂ ∂ωz/∂θ₃ ∂ωz/∂θ₄ ∂ωz/∂θ₅ ∂ωz/∂θ₆ |
The first three rows correspond to the linear velocities: vx, vy, vz. The last three rows correspond to the angular velocities: roll (ωx), pitch (ωy), and yaw (ωz). θ₁, θ₂, θ₃, θ₄, θ₅, θ₆ are the joint angles. ∂ denotes a partial derivative.
Implementations§
Source§impl Jacobian
impl Jacobian
Sourcepub fn new(robot: &impl Kinematics, qs: &Joints, epsilon: f64) -> Self
pub fn new(robot: &impl Kinematics, qs: &Joints, epsilon: f64) -> Self
Constructs a new Jacobian struct by computing the Jacobian matrix for the given robot and joint configuration
§Arguments
robot
- A reference to the robot implementing the Kinematics traitqs
- A reference to the joint configurationepsilon
- A small value used for numerical differentiation
§Returns
A new instance of Jacobian
Examples found in repository?
10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63
fn main() {
let robot = OPWKinematics::new_with_constraints(
Parameters::irb2400_10(), Constraints::new(
[-0.1, 0.0, 0.0, 0.0, -PI, -PI],
[PI, PI, 2.0 * PI, PI, PI, PI],
BY_CONSTRAINS,
));
let joints: Joints = [0.0, 0.1, 0.2, 0.3, 0.0, 0.5]; // Joints are alias of [f64; 6]
let jakobian = rs_opw_kinematics::jacobian::Jacobian::new(&robot, &joints, 1E-6);
let desired_velocity_isometry =
Isometry3::new(Vector3::new(0.0, 1.0, 0.0),
Vector3::new(0.0, 0.0, 1.0));
let joint_velocities = jakobian.velocities(&desired_velocity_isometry);
println!("Computed joint velocities: {:?}", joint_velocities.unwrap());
let desired_force_torque =
Isometry3::new(Vector3::new(0.0, 0.0, 0.0),
Vector3::new(0.0, 0.0, 1.234));
let joint_torques = jakobian.torques(&desired_force_torque);
println!("Computed joint torques: {:?}", joint_torques);
// Robot with the tool, standing on a base:
let robot_alone = OPWKinematics::new(Parameters::staubli_tx2_160l());
// 1 meter high pedestal
let pedestal = 0.5;
let base_translation = Isometry3::from_parts(
Translation3::new(0.0, 0.0, pedestal).into(),
UnitQuaternion::identity(),
);
let robot_with_base = rs_opw_kinematics::tool::Base {
robot: Arc::new(robot_alone),
base: base_translation,
};
// Tool extends 1 meter in the Z direction, envisioning something like sword
let sword = 1.0;
let tool_translation = Isometry3::from_parts(
Translation3::new(0.0, 0.0, sword).into(),
UnitQuaternion::identity(),
);
// Create the Tool instance with the transformation
let robot_complete = rs_opw_kinematics::tool::Tool {
robot: Arc::new(robot_with_base),
tool: tool_translation,
};
let tcp_pose: Pose = robot_complete.forward(&joints);
println!("The sword tip is at: {:?}", tcp_pose);
}
Sourcepub fn velocities(
&self,
desired_end_effector_velocity: &Isometry3<f64>,
) -> Result<Joints, &'static str>
pub fn velocities( &self, desired_end_effector_velocity: &Isometry3<f64>, ) -> Result<Joints, &'static str>
Computes the joint velocities required to achieve a desired end-effector velocity:
Q’ = J⁻¹ x’
where Q’ are joint velocities, J⁻¹ is the inverted Jacobian matrix and x’ is the vector of velocities of the tool center point. First 3 components are velocities along x,y and z axis, the other 3 are angular rotation velocities around x (roll), y (pitch) and z (yaw) axis
§Arguments
desired_end_effector_velocity
- An Isometry3 representing the desired linear and angular velocity of the end-effector. The x’ vector is extracted from the isometry.
§Returns
Result<Joints, &'static str>
- Joint positions, with values representing joint velocities rather than angles,
or an error message if the computation fails.
This method extracts the linear and angular velocities from the provided Isometry3
and combines them into a single 6D vector. It then computes the joint velocities required
to achieve the desired end-effector velocity using the velocities_from_vector
method.
Examples found in repository?
10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63
fn main() {
let robot = OPWKinematics::new_with_constraints(
Parameters::irb2400_10(), Constraints::new(
[-0.1, 0.0, 0.0, 0.0, -PI, -PI],
[PI, PI, 2.0 * PI, PI, PI, PI],
BY_CONSTRAINS,
));
let joints: Joints = [0.0, 0.1, 0.2, 0.3, 0.0, 0.5]; // Joints are alias of [f64; 6]
let jakobian = rs_opw_kinematics::jacobian::Jacobian::new(&robot, &joints, 1E-6);
let desired_velocity_isometry =
Isometry3::new(Vector3::new(0.0, 1.0, 0.0),
Vector3::new(0.0, 0.0, 1.0));
let joint_velocities = jakobian.velocities(&desired_velocity_isometry);
println!("Computed joint velocities: {:?}", joint_velocities.unwrap());
let desired_force_torque =
Isometry3::new(Vector3::new(0.0, 0.0, 0.0),
Vector3::new(0.0, 0.0, 1.234));
let joint_torques = jakobian.torques(&desired_force_torque);
println!("Computed joint torques: {:?}", joint_torques);
// Robot with the tool, standing on a base:
let robot_alone = OPWKinematics::new(Parameters::staubli_tx2_160l());
// 1 meter high pedestal
let pedestal = 0.5;
let base_translation = Isometry3::from_parts(
Translation3::new(0.0, 0.0, pedestal).into(),
UnitQuaternion::identity(),
);
let robot_with_base = rs_opw_kinematics::tool::Base {
robot: Arc::new(robot_alone),
base: base_translation,
};
// Tool extends 1 meter in the Z direction, envisioning something like sword
let sword = 1.0;
let tool_translation = Isometry3::from_parts(
Translation3::new(0.0, 0.0, sword).into(),
UnitQuaternion::identity(),
);
// Create the Tool instance with the transformation
let robot_complete = rs_opw_kinematics::tool::Tool {
robot: Arc::new(robot_with_base),
tool: tool_translation,
};
let tcp_pose: Pose = robot_complete.forward(&joints);
println!("The sword tip is at: {:?}", tcp_pose);
}
Sourcepub fn velocities_fixed(
&self,
vx: f64,
vy: f64,
vz: f64,
) -> Result<Joints, &'static str>
pub fn velocities_fixed( &self, vx: f64, vy: f64, vz: f64, ) -> Result<Joints, &'static str>
Computes the joint velocities required to achieve a desired end-effector velocity:
Q’ = J⁻¹ x’
where Q’ are joint velocities, J⁻¹ is the inverted Jacobian matrix and x’ is the vector of velocities of the tool center point. First 3 components are velocities along x,y and z axis. The remaining 3 are angular rotation velocities are assumed to be zero.
§Arguments
vx, vy, vz
- x, y and z components of end effector velocity (linear).
§Returns
Result<Joints, &'static str>
- Joint positions, with values representing
joint velocities rather than angles or an error message if the computation fails.
Sourcepub fn velocities_from_vector(
&self,
X: &Vector6<f64>,
) -> Result<Joints, &'static str>
pub fn velocities_from_vector( &self, X: &Vector6<f64>, ) -> Result<Joints, &'static str>
Computes the joint velocities required to achieve a desired end-effector velocity:
Q’ = J⁻¹ X’
where Q’ are joint velocities, J⁻¹ is the inverted Jacobian matrix and x’ is the vector of velocities of the tool center point. First 3 components are velocities along x,y and z axis, the other 3 are angular rotation velocities around x (roll), y (pitch) and z (yaw) axis
§Arguments
X'
- A 6D vector representing the desired linear and angular velocity of the end-effector as defined above.
§Returns
Result<Joints, &'static str>
- Joint positions, with values representing joint velocities rather than angles,
or an error message if the computation fails.
This method tries to compute the joint velocities using the inverse of the Jacobian matrix. If the Jacobian matrix is not invertible, it falls back to using the pseudoinverse.
Sourcepub fn torques(&self, desired_force_isometry: &Isometry3<f64>) -> Joints
pub fn torques(&self, desired_force_isometry: &Isometry3<f64>) -> Joints
Computes the joint torques required to achieve a desired end-effector force/torque This function computes
t = JᵀF
where Jᵀ is transposed Jacobian as defined above and f is the desired force vector that is extracted from the passed Isometry3.
§Arguments
desired_force_torque
- isometry structure representing forces (in Newtons, N) and torgues (in Newton - meters, Nm) rather than dimensions and angles.
§Returns
Joint positions, with values representing joint torques, or an error message if the computation fails.
Examples found in repository?
10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63
fn main() {
let robot = OPWKinematics::new_with_constraints(
Parameters::irb2400_10(), Constraints::new(
[-0.1, 0.0, 0.0, 0.0, -PI, -PI],
[PI, PI, 2.0 * PI, PI, PI, PI],
BY_CONSTRAINS,
));
let joints: Joints = [0.0, 0.1, 0.2, 0.3, 0.0, 0.5]; // Joints are alias of [f64; 6]
let jakobian = rs_opw_kinematics::jacobian::Jacobian::new(&robot, &joints, 1E-6);
let desired_velocity_isometry =
Isometry3::new(Vector3::new(0.0, 1.0, 0.0),
Vector3::new(0.0, 0.0, 1.0));
let joint_velocities = jakobian.velocities(&desired_velocity_isometry);
println!("Computed joint velocities: {:?}", joint_velocities.unwrap());
let desired_force_torque =
Isometry3::new(Vector3::new(0.0, 0.0, 0.0),
Vector3::new(0.0, 0.0, 1.234));
let joint_torques = jakobian.torques(&desired_force_torque);
println!("Computed joint torques: {:?}", joint_torques);
// Robot with the tool, standing on a base:
let robot_alone = OPWKinematics::new(Parameters::staubli_tx2_160l());
// 1 meter high pedestal
let pedestal = 0.5;
let base_translation = Isometry3::from_parts(
Translation3::new(0.0, 0.0, pedestal).into(),
UnitQuaternion::identity(),
);
let robot_with_base = rs_opw_kinematics::tool::Base {
robot: Arc::new(robot_alone),
base: base_translation,
};
// Tool extends 1 meter in the Z direction, envisioning something like sword
let sword = 1.0;
let tool_translation = Isometry3::from_parts(
Translation3::new(0.0, 0.0, sword).into(),
UnitQuaternion::identity(),
);
// Create the Tool instance with the transformation
let robot_complete = rs_opw_kinematics::tool::Tool {
robot: Arc::new(robot_with_base),
tool: tool_translation,
};
let tcp_pose: Pose = robot_complete.forward(&joints);
println!("The sword tip is at: {:?}", tcp_pose);
}
Sourcepub fn torques_from_vector(&self, F: &Vector6<f64>) -> Joints
pub fn torques_from_vector(&self, F: &Vector6<f64>) -> Joints
Computes the joint torques required to achieve a desired end-effector force/torque This function computes
t = JᵀF
where Jᵀ is transposed Jacobian as defined above and f is the desired force and torgue vector. The first 3 components are forces along x, y and z in Newtons, the other 3 components are rotations around x (roll), y (pitch) and z (yaw) axis in Newton meters.
§Arguments
F
- A 6D vector representing the desired force and torque at the end-effector as explained above.
§Returns
Joint positions, with values representing joint torques, or an error message if the computation fails.
Auto Trait Implementations§
impl Freeze for Jacobian
impl RefUnwindSafe for Jacobian
impl Send for Jacobian
impl Sync for Jacobian
impl Unpin for Jacobian
impl UnwindSafe for Jacobian
Blanket Implementations§
Source§impl<T, U> AsBindGroupShaderType<U> for T
impl<T, U> AsBindGroupShaderType<U> for T
Source§fn as_bind_group_shader_type(&self, _images: &RenderAssets<Image>) -> U
fn as_bind_group_shader_type(&self, _images: &RenderAssets<Image>) -> U
T
ShaderType
for self
. When used in AsBindGroup
derives, it is safe to assume that all images in self
exist.Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Source§impl<T> Downcast for Twhere
T: Any,
impl<T> Downcast for Twhere
T: Any,
Source§fn into_any(self: Box<T>) -> Box<dyn Any>
fn into_any(self: Box<T>) -> Box<dyn Any>
Box<dyn Trait>
(where Trait: Downcast
) to Box<dyn Any>
. Box<dyn Any>
can
then be further downcast
into Box<ConcreteType>
where ConcreteType
implements Trait
.Source§fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>
fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>
Rc<Trait>
(where Trait: Downcast
) to Rc<Any>
. Rc<Any>
can then be
further downcast
into Rc<ConcreteType>
where ConcreteType
implements Trait
.Source§fn as_any(&self) -> &(dyn Any + 'static)
fn as_any(&self) -> &(dyn Any + 'static)
&Trait
(where Trait: Downcast
) to &Any
. This is needed since Rust cannot
generate &Any
’s vtable from &Trait
’s.Source§fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
&mut Trait
(where Trait: Downcast
) to &Any
. This is needed since Rust cannot
generate &mut Any
’s vtable from &mut Trait
’s.Source§impl<T> DowncastSync for T
impl<T> DowncastSync for T
Source§impl<T> Instrument for T
impl<T> Instrument for T
Source§fn instrument(self, span: Span) -> Instrumented<Self>
fn instrument(self, span: Span) -> Instrumented<Self>
Source§fn in_current_span(self) -> Instrumented<Self>
fn in_current_span(self) -> Instrumented<Self>
Source§impl<T> IntoEither for T
impl<T> IntoEither for T
Source§fn into_either(self, into_left: bool) -> Either<Self, Self>
fn into_either(self, into_left: bool) -> Either<Self, Self>
self
into a Left
variant of Either<Self, Self>
if into_left
is true
.
Converts self
into a Right
variant of Either<Self, Self>
otherwise. Read moreSource§fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
self
into a Left
variant of Either<Self, Self>
if into_left(&self)
returns true
.
Converts self
into a Right
variant of Either<Self, Self>
otherwise. Read moreSource§impl<T> Pointable for T
impl<T> Pointable for T
Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self
from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self
is actually part of its subset T
(and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset
but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self
to the equivalent element of its superset.