pub struct Constraints {
pub from: [f64; 6],
pub to: [f64; 6],
pub centers: [f64; 6],
pub tolerances: [f64; 6],
pub sorting_weight: f64,
}Fields§
§from: [f64; 6]Normalized lower limit. If more than upper limit, the range wraps-around through 0
to: [f64; 6]Normalized upper limit. If less than lower limit, the range wraps-around through 0
centers: [f64; 6]§tolerances: [f64; 6]§sorting_weight: f64Used when sorting the solutions by both middle values of the constraints and the previous values of the joints. 1.0 gives the absolute priority to constraints, 0.0. gives absolute priority for joints.
Implementations§
Source§impl Constraints
impl Constraints
Sourcepub fn new(from: Joints, to: Joints, sorting_weight: f64) -> Self
pub fn new(from: Joints, to: Joints, sorting_weight: f64) -> Self
Create constraints that restrict the joint rotations between ‘from’ to ‘to’ values. Wrapping arround is supported so order is important. For instance, from = 0.1 and to = 0.2 (radians) means the joint is allowed to rotate to 0.11, 0.12 … 1.99, 0.2. from = 0.2 ant to = 0.1 is also valid but means the joint is allowed to rotate to 0.21, 0.22, 0.99, 2 * PI or 0.0 (wrapping around), then to 0.09 and finally 0.1, so the other side of the circle. The sorting_weight parameter influences sorting of the results: 0.0 (or BY_PREV) gives absolute priority to the previous values of the joints, 1.0 (or BY_CONSTRAINTS) gives absolute priority to the middle values of constraints. Intermediate values like 0.5 provide the weighted compromise.
Sourcepub fn from_degrees(
ranges: [RangeInclusive<f64>; 6],
sorting_weight: f64,
) -> Self
pub fn from_degrees( ranges: [RangeInclusive<f64>; 6], sorting_weight: f64, ) -> Self
Initializes Constraints from an array of 6 ranges (RangeInclusive<f64>),
where each range specifies the from (start) and to (end) values for each joint.
This is convenience method, where VALUES MUST BE GIVEN IN DEGREES.
§Parameters
ranges: An array of 6RangeInclusive<f64>values, each representing a range for one joint.- The start of each range is taken as the
frombound. - The end of each range is taken as the
tobound.
- The start of each range is taken as the
sorting_weight: Af64value representing the sorting weight for the constraint.
§Returns
A new instance of Constraints with from, to, centers, and tolerances calculated
based on the specified ranges.
§Example
use rs_opw_kinematics::constraints::{Constraints, BY_PREV};
let constraints = Constraints::from_degrees(
[0.0..=90.0, 45.0..=135.0, -90.0..=90.0, 0.0..=180.0, -45.0..=45.0, -180.0..=180.0],
BY_PREV);pub fn update_range(&mut self, from: Joints, to: Joints)
Sourcepub fn compliant(&self, angles: &[f64; 6]) -> bool
pub fn compliant(&self, angles: &[f64; 6]) -> bool
Checks if all values in the given vector or angles satisfy these constraints.
Sourcepub fn filter(&self, angles: &Vec<[f64; 6]>) -> Vec<[f64; 6]>
pub fn filter(&self, angles: &Vec<[f64; 6]>) -> Vec<[f64; 6]>
Return new vector of angle arrays, removing all that have members not satisfying these constraints.
pub fn to_yaml(&self) -> String
Sourcepub fn random_angles(&self) -> Joints
pub fn random_angles(&self) -> Joints
Generate a random valid angle within the defined constraints for each joint.
Trait Implementations§
Source§impl Clone for Constraints
impl Clone for Constraints
Source§fn clone(&self) -> Constraints
fn clone(&self) -> Constraints
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for Constraints
impl Debug for Constraints
Source§impl Default for Constraints
impl Default for Constraints
impl Copy for Constraints
Auto Trait Implementations§
impl Freeze for Constraints
impl RefUnwindSafe for Constraints
impl Send for Constraints
impl Sync for Constraints
impl Unpin for Constraints
impl UnwindSafe for Constraints
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> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
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> FromWorld for Twhere
T: Default,
impl<T> FromWorld for Twhere
T: Default,
Source§fn from_world(_world: &mut World) -> T
fn from_world(_world: &mut World) -> T
Self using data from the given World.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.