rs_opw_kinematics::frame

Struct Frame

Source
pub struct Frame {
    pub robot: Arc<dyn Kinematics>,
    pub frame: Isometry3<f64>,
}
Expand description

Defines the frame that transforms the robot working area, moving and rotating it (not stretching). The frame can be created from 3 pairs of points, one defining the points before transforming and another after, or alternatively 1 pair is enough if we assume there is no rotation.

Fields§

§robot: Arc<dyn Kinematics>§frame: Isometry3<f64>

The frame transform, normally computed with either Frame::translation or Frame::isometry

Implementations§

Source§

impl Frame

Source

pub fn translation(p: Point3<f64>, q: Point3<f64>) -> Isometry3<f64>

Compute the frame transform that may include only shift (but not rotation)

Examples found in repository?
examples/frame.rs (lines 13-15)
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
fn main() {
    let robot = OPWKinematics::new(Parameters::irb2400_10());
    // Shift not too much to have values close to previous
    let frame_transform = Frame::translation(
        Point3::new(0.0, 0.0, 0.0), 
        Point3::new(0.011, 0.022, 0.033));

    let framed = Frame {
        robot: Arc::new(robot),
        frame: frame_transform,
    };
    let joints_no_frame: [f64; 6] = [0.0, 0.11, 0.22, 0.3, 0.1, 0.5]; // without frame

    println!("No frame transform:");
    dump_joints(&joints_no_frame);

    println!("Possible joint values after the frame transform:");
    let (solutions, _transformed_pose) = framed.forward_transformed(
        &joints_no_frame, &joints_no_frame);
    dump_solutions(&solutions);

    let framed = robot.forward(&solutions[0]).translation;
    let unframed = robot.forward(&joints_no_frame).translation;

    println!("Distance between framed and not framed pose {:.3} {:.3} {:.3}",
             framed.x - unframed.x, framed.y - unframed.y, framed.z - unframed.z);
}
Source

pub fn frame( p1: Point3<f64>, p2: Point3<f64>, p3: Point3<f64>, q1: Point3<f64>, q2: Point3<f64>, q3: Point3<f64>, ) -> Result<Isometry3<f64>, Box<dyn Error>>

Compute the frame transform that may include shift and rotation (but not stretching)

Source

pub fn forward_transformed( &self, qs: &Joints, previous: &Joints, ) -> (Solutions, Pose)

This function calculates the required joint values for a robot after applying a transformation to the tool center point (TCP) location, as defined by a specified frame. It uses the provided joint positions (qs) and the previous joint positions to compute the new positions. Depending on how the frame is defined, there can be no solutions or multiple solutions; hence, the function returns a Solutions structure to account for this variability. Additionally, this method returns the transformed tool center pose.

§Arguments
  • qs - A reference to the Joints structure representing the initial joint positions before the transformation.
  • previous - A reference to the Joints structure representing the previous joint positions.
§Returns

A tuple containing:

  • Solutions - A structure containing the possible joint positions after transformation.
  • Pose - The transformed tool center pose.
§Example
use std::sync::Arc;
use nalgebra::Point3;
use rs_opw_kinematics::frame::Frame;
use rs_opw_kinematics::kinematics_impl::OPWKinematics;
use rs_opw_kinematics::parameters::opw_kinematics::Parameters;

let robot = OPWKinematics::new(Parameters::irb2400_10());
let frame_transform = Frame::translation(
  Point3::new(0.0, 0.0, 0.0), Point3::new(0.01, 0.00, 0.0));
let framed = rs_opw_kinematics::frame::Frame {
  robot: Arc::new(robot),
  frame: frame_transform,
};
let joints_no_frame: [f64; 6] = [0.0, 0.11, 0.22, 0.3, 0.1, 0.5]; // without frame
let (solutions, _transformed_pose) = framed.forward_transformed(
  &joints_no_frame, &joints_no_frame /* prioritize closest to this value */);
// Use solutions and transformed_pose as needed
Examples found in repository?
examples/frame.rs (lines 27-28)
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
fn main() {
    let robot = OPWKinematics::new(Parameters::irb2400_10());
    // Shift not too much to have values close to previous
    let frame_transform = Frame::translation(
        Point3::new(0.0, 0.0, 0.0), 
        Point3::new(0.011, 0.022, 0.033));

    let framed = Frame {
        robot: Arc::new(robot),
        frame: frame_transform,
    };
    let joints_no_frame: [f64; 6] = [0.0, 0.11, 0.22, 0.3, 0.1, 0.5]; // without frame

    println!("No frame transform:");
    dump_joints(&joints_no_frame);

    println!("Possible joint values after the frame transform:");
    let (solutions, _transformed_pose) = framed.forward_transformed(
        &joints_no_frame, &joints_no_frame);
    dump_solutions(&solutions);

    let framed = robot.forward(&solutions[0]).translation;
    let unframed = robot.forward(&joints_no_frame).translation;

    println!("Distance between framed and not framed pose {:.3} {:.3} {:.3}",
             framed.x - unframed.x, framed.y - unframed.y, framed.z - unframed.z);
}

Trait Implementations§

Source§

impl Kinematics for Frame

Source§

fn inverse(&self, tcp: &Pose) -> Solutions

Find inverse kinematics (joint position) for this pose This function is faster but does not handle the singularity J5 = 0 well. All returned solutions are cross-checked with forward kinematics and valid.
Source§

fn inverse_5dof(&self, tcp: &Pose, j6: f64) -> Solutions

Calculates the inverse kinematics for a robot while ignoring the rotation around joint 6. The position of the tool center point remains precise, but the rotation is approximate (rotation around the tool axis is ignored). The return value for joint 6 is set according to the provided parameter. This method is significantly faster
Source§

fn inverse_continuing_5dof(&self, tcp: &Pose, previous: &Joints) -> Solutions

Calculates the inverse kinematics for a robot while ignoring the rotation around joint 6. The position of the tool center point remains precise, but the rotation is approximate (rotation around the tool axis is ignored). The return value for joint 6 is set based on the previous joint values. This method is significantly faster
Source§

fn inverse_continuing(&self, tcp: &Pose, previous: &Joints) -> Solutions

Find inverse kinematics (joint position) for this pose This function handles the singularity J5 = 0 by keeping the previous values the values J4 and J6 from the previous solution Use CONSTRAINT_CENTERED as previous if there is no previous position but we prefer to be as close to the center of constraints (or zeroes if not set) as possible.
Source§

fn forward(&self, qs: &Joints) -> Pose

Find forward kinematics (pose from joint positions). For 5 DOF robot, the rotation of the joint 6 should normally be 0.0 but some other value can be given, meaning the tool is mounted with fixed rotation offset.
Source§

fn forward_with_joint_poses(&self, joints: &Joints) -> [Pose; 6]

Computes the forward kinematics for a 6-DOF robotic arm and returns an array of poses representing the position and orientation of each joint, including the final end-effector. Read more
Source§

fn kinematic_singularity(&self, qs: &Joints) -> Option<Singularity>

Detect the singularity. Returns either A type singlularity or None if no singularity detected.
Source§

fn constraints(&self) -> &Option<Constraints>

Returns constraints under what the solver is operating. Constraints are remembered here and can be used for generating random joint angles needed by RRT, or say providing limits of sliders in GUI.

Auto Trait Implementations§

§

impl Freeze for Frame

§

impl !RefUnwindSafe for Frame

§

impl Send for Frame

§

impl Sync for Frame

§

impl Unpin for Frame

§

impl !UnwindSafe for Frame

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T, U> AsBindGroupShaderType<U> for T
where U: ShaderType, &'a T: for<'a> Into<U>,

Source§

fn as_bind_group_shader_type(&self, _images: &RenderAssets<Image>) -> U

Return the T ShaderType for self. When used in AsBindGroup derives, it is safe to assume that all images in self exist.
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> Downcast<T> for T

Source§

fn downcast(&self) -> &T

Source§

impl<T> Downcast for T
where T: Any,

Source§

fn into_any(self: Box<T>) -> Box<dyn Any>

Convert 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>

Convert 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)

Convert &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)

Convert &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
where T: Any + Send + Sync,

Source§

fn into_any_arc(self: Arc<T>) -> Arc<dyn Any + Send + Sync>

Convert Arc<Trait> (where Trait: Downcast) to Arc<Any>. Arc<Any> can then be further downcast into Arc<ConcreteType> where ConcreteType implements Trait.
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T> Instrument for T

Source§

fn instrument(self, span: Span) -> Instrumented<Self>

Instruments this type with the provided Span, returning an Instrumented wrapper. Read more
Source§

fn in_current_span(self) -> Instrumented<Self>

Instruments this type with the current Span, returning an Instrumented wrapper. Read more
Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> IntoEither for T

Source§

fn into_either(self, into_left: bool) -> Either<Self, Self>

Converts 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 more
Source§

fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
where F: FnOnce(&Self) -> bool,

Converts 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 more
Source§

impl<T> Pointable for T

Source§

const ALIGN: usize

The alignment of pointer.
Source§

type Init = T

The type for initializers.
Source§

unsafe fn init(init: <T as Pointable>::Init) -> usize

Initializes a with the given initializer. Read more
Source§

unsafe fn deref<'a>(ptr: usize) -> &'a T

Dereferences the given pointer. Read more
Source§

unsafe fn deref_mut<'a>(ptr: usize) -> &'a mut T

Mutably dereferences the given pointer. Read more
Source§

unsafe fn drop(ptr: usize)

Drops the object pointed to by the given pointer. Read more
Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

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

fn is_in_subset(&self) -> bool

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

fn to_subset_unchecked(&self) -> SS

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

fn from_subset(element: &SS) -> SP

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

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

impl<T> Upcast<T> for T

Source§

fn upcast(&self) -> Option<&T>

Source§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

Source§

fn vzip(self) -> V

Source§

impl<T> WithSubscriber for T

Source§

fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>
where S: Into<Dispatch>,

Attaches the provided Subscriber to this type, returning a WithDispatch wrapper. Read more
Source§

fn with_current_subscriber(self) -> WithDispatch<Self>

Attaches the current default Subscriber to this type, returning a WithDispatch wrapper. Read more
Source§

impl<T> ErasedDestructor for T
where T: 'static,

Source§

impl<T> MaybeSendSync for T

Source§

impl<T> Settings for T
where T: 'static + Send + Sync,

Source§

impl<T> WasmNotSend for T
where T: Send,

Source§

impl<T> WasmNotSync for T
where T: Sync,