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
impl Frame
Sourcepub fn translation(p: Point3<f64>, q: Point3<f64>) -> Isometry3<f64>
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?
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);
}
Sourcepub 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>>
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)
Sourcepub fn forward_transformed(
&self,
qs: &Joints,
previous: &Joints,
) -> (Solutions, Pose)
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 theJoints
structure representing the initial joint positions before the transformation.previous
- A reference to theJoints
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?
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
impl Kinematics for Frame
Source§fn inverse(&self, tcp: &Pose) -> Solutions
fn inverse(&self, tcp: &Pose) -> Solutions
Source§fn inverse_5dof(&self, tcp: &Pose, j6: f64) -> Solutions
fn inverse_5dof(&self, tcp: &Pose, j6: f64) -> Solutions
Source§fn inverse_continuing_5dof(&self, tcp: &Pose, previous: &Joints) -> Solutions
fn inverse_continuing_5dof(&self, tcp: &Pose, previous: &Joints) -> Solutions
Source§fn inverse_continuing(&self, tcp: &Pose, previous: &Joints) -> Solutions
fn inverse_continuing(&self, tcp: &Pose, previous: &Joints) -> Solutions
Source§fn forward(&self, qs: &Joints) -> Pose
fn forward(&self, qs: &Joints) -> Pose
Source§fn forward_with_joint_poses(&self, joints: &Joints) -> [Pose; 6]
fn forward_with_joint_poses(&self, joints: &Joints) -> [Pose; 6]
Source§fn kinematic_singularity(&self, qs: &Joints) -> Option<Singularity>
fn kinematic_singularity(&self, qs: &Joints) -> Option<Singularity>
Source§fn constraints(&self) -> &Option<Constraints>
fn constraints(&self) -> &Option<Constraints>
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, 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.