pub struct KinematicsWithShape {
pub kinematics: Arc<dyn Kinematics>,
pub body: RobotBody,
}Expand description
Struct that combines the kinematic model of a robot with its geometrical shape. This struct provides both the kinematic functionality for computing joint positions and the physical structure used for collision detection and other geometric calculations.
Fields§
§kinematics: Arc<dyn Kinematics>The kinematic model of the robot, typically used to compute forward and inverse kinematics.
This is an abstract trait (Kinematics), allowing for different implementations of kinematic models.
body: RobotBodyThe physical structure of the robot, represented by its joint geometries.
This RobotBody contains information about the geometrical shapes of the joints
and provides functionality for collision detection.
Implementations§
Source§impl KinematicsWithShape
impl KinematicsWithShape
Sourcepub fn new(
opw_parameters: Parameters,
constraints: Constraints,
joint_meshes: [TriMesh; 6],
base_mesh: TriMesh,
base_transform: Isometry3<f64>,
tool_mesh: TriMesh,
tool_transform: Isometry3<f64>,
collision_environment: Vec<CollisionBody>,
first_collision_only: bool,
) -> Self
pub fn new( opw_parameters: Parameters, constraints: Constraints, joint_meshes: [TriMesh; 6], base_mesh: TriMesh, base_transform: Isometry3<f64>, tool_mesh: TriMesh, tool_transform: Isometry3<f64>, collision_environment: Vec<CollisionBody>, first_collision_only: bool, ) -> Self
Constructs a new KinematicsWithShape instance for a 6DOF robot.
This method consumes all parameters, moving them inside the robot.
This is important for meshes that are bulky.
§Parameters
-
opw_parameters- OPW parameters defining this robot -
constraints: joint constraint limits -
joint_meshes- An array of [TriMesh; 6] representing the meshes for each joint’s body. -
base_mesh- The mesh of the robot base. -
base_transform- The transform to apply to the base mesh. This transform brings the robot into its intended location inside the robotic cell. -
tool_mesh- The mesh of the robot’s tool, which will also be checked for collisions. -
tool_transform- The transform to apply to the tool mesh. It defines the location of the “action point” of the robot whose location and rotation (pose) is the pose for direct and inverse kinematics calls. -
collision_environment- A vector of collision objects represented byCollisionBody, where each object includes a mesh and its transform. -
first_pose_only- As collision check may be expensive, check if we need multiple checked solutions if inverse kinematics, or the first (best) is enough
§Returns
A KinematicsWithShape instance with defined kinematic structure and shapes for collision detection.
Sourcepub fn with_safety(
opw_parameters: Parameters,
constraints: Constraints,
joint_meshes: [TriMesh; 6],
base_mesh: TriMesh,
base_transform: Isometry3<f64>,
tool_mesh: TriMesh,
tool_transform: Isometry3<f64>,
collision_environment: Vec<CollisionBody>,
safety: SafetyDistances,
) -> Self
pub fn with_safety( opw_parameters: Parameters, constraints: Constraints, joint_meshes: [TriMesh; 6], base_mesh: TriMesh, base_transform: Isometry3<f64>, tool_mesh: TriMesh, tool_transform: Isometry3<f64>, collision_environment: Vec<CollisionBody>, safety: SafetyDistances, ) -> Self
Constructs a new KinematicsWithShape instance for a 6DOF robot.
This method consumes all parameters, moving them inside the robot.
This is important for meshes that are bulky.
§Parameters
-
opw_parameters- OPW parameters defining this robot -
constraints: joint constraint limits -
joint_meshes- An array of [TriMesh; 6] representing the meshes for each joint’s body. -
base_mesh- The mesh of the robot base. -
base_transform- The transform to apply to the base mesh. This transform brings the robot into its intended location inside the robotic cell. -
tool_mesh- The mesh of the robot’s tool, which will also be checked for collisions. -
tool_transform- The transform to apply to the tool mesh. It defines the location of the “action point” of the robot whose location and rotation (pose) is the pose for direct and inverse kinematics calls. -
collision_environment- A vector of collision objects represented byCollisionBody, where each object includes a mesh and its transform. -
safety- defines the minimal allowed distances between collision objects and specifies other details on how collisions are checked. In practice robot must stay at some safe distance from collision objects rather than touching them.
§Returns
A KinematicsWithShape instance with defined kinematic structure and shapes for collision detection.
Source§impl KinematicsWithShape
impl KinematicsWithShape
Sourcepub fn positioned_robot(&self, joint_positions: &Joints) -> PositionedRobot<'_>
pub fn positioned_robot(&self, joint_positions: &Joints) -> PositionedRobot<'_>
Method to compute and return a PositionedRobot from the current RobotBody and a set of joint positions.
This method uses the forward kinematics to compute the global transforms of each joint
and then creates the corresponding PositionedJoint instances, which are collected into a PositionedRobot.
§Arguments
joint_positions- A reference to the joint values (angles/positions) to compute the forward kinematics.
§Returns
- A new instance of
PositionedRobotcontaining the positioned joints with precomputed transforms.
Source§impl KinematicsWithShape
impl KinematicsWithShape
Sourcepub fn collides(&self, joints: &Joints) -> bool
pub fn collides(&self, joints: &Joints) -> bool
Check for collisions for the given joint position. Both self-collisions and collisions with environment are checked. This method simply returns true (if collides) or false (if not)
Sourcepub fn non_colliding_offsets(
&self,
joints: &Joints,
from: &Joints,
to: &Joints,
) -> Solutions
pub fn non_colliding_offsets( &self, joints: &Joints, from: &Joints, to: &Joints, ) -> Solutions
Return non colliding offsets, tweaking each joint plus minus either side, either into ‘to’ or into ‘from’. This is required for planning algorithms like A*. We can do less collision checks as we only need to check the joint branch of the robot we moved.
Trait Implementations§
Source§impl Kinematics for KinematicsWithShape
impl Kinematics for KinematicsWithShape
Source§fn inverse(&self, pose: &Pose) -> Solutions
fn inverse(&self, pose: &Pose) -> Solutions
Delegates call to underlying Kinematics, but will filter away colliding poses
Source§fn inverse_continuing(&self, pose: &Pose, previous: &Joints) -> Solutions
fn inverse_continuing(&self, pose: &Pose, previous: &Joints) -> Solutions
Delegates call to underlying Kinematics, but will filter away colliding poses
Source§fn inverse_5dof(&self, pose: &Pose, j6: f64) -> Solutions
fn inverse_5dof(&self, pose: &Pose, j6: f64) -> Solutions
Delegates call to underlying Kinematics, but will filter away colliding poses
Source§fn inverse_continuing_5dof(&self, pose: &Pose, prev: &Joints) -> Solutions
fn inverse_continuing_5dof(&self, pose: &Pose, prev: &Joints) -> Solutions
Delegates call to underlying Kinematics, but will filter away colliding poses
Source§fn forward(&self, qs: &Joints) -> Pose
fn forward(&self, qs: &Joints) -> Pose
Source§fn constraints(&self) -> &Option<Constraints>
fn constraints(&self) -> &Option<Constraints>
Source§fn kinematic_singularity(&self, qs: &Joints) -> Option<Singularity>
fn kinematic_singularity(&self, qs: &Joints) -> Option<Singularity>
Auto Trait Implementations§
impl Freeze for KinematicsWithShape
impl !RefUnwindSafe for KinematicsWithShape
impl Send for KinematicsWithShape
impl Sync for KinematicsWithShape
impl Unpin for KinematicsWithShape
impl !UnwindSafe for KinematicsWithShape
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<GpuImage>) -> U
fn as_bind_group_shader_type(&self, _images: &RenderAssets<GpuImage>) -> 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>, which can then be
downcast into Box<dyn 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>, which 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> 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> DowncastSend for T
impl<T> DowncastSend for T
Source§impl<T> DowncastSync for T
impl<T> DowncastSync for T
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.