Struct openrr_planner::RandomInitializeIkSolver [−][src]
pub struct RandomInitializeIkSolver<T, I> where
I: InverseKinematicsSolver<T>,
T: RealField, { pub solver: I, pub num_max_try: usize, // some fields omitted }
Expand description
Randomize initial joint angles before solving
Fields
solver: I
The IK solver to be used after set random joint angles
num_max_try: usize
The number to try to solve
Implementations
Trait Implementations
impl<T: Debug, I: Debug> Debug for RandomInitializeIkSolver<T, I> where
I: InverseKinematicsSolver<T>,
T: RealField,
impl<T: Debug, I: Debug> Debug for RandomInitializeIkSolver<T, I> where
I: InverseKinematicsSolver<T>,
T: RealField,
impl<T, I> InverseKinematicsSolver<T> for RandomInitializeIkSolver<T, I> where
T: RealField + SubsetOf<f64>,
I: InverseKinematicsSolver<T>,
impl<T, I> InverseKinematicsSolver<T> for RandomInitializeIkSolver<T, I> where
T: RealField + SubsetOf<f64>,
I: InverseKinematicsSolver<T>,
fn solve_with_constraints(
&self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>,
constraints: &Constraints
) -> Result<(), Error>
fn solve_with_constraints(
&self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>,
constraints: &Constraints
) -> Result<(), Error>
Move the end transform of the arm
to target_pose
with constraints
fn solve(
&self,
arm: &SerialChain<T>,
target_pose: &Isometry<T, Unit<Quaternion<T>>, 3_usize>
) -> Result<(), Error>
fn solve(
&self,
arm: &SerialChain<T>,
target_pose: &Isometry<T, Unit<Quaternion<T>>, 3_usize>
) -> Result<(), Error>
Move the end transform of the arm
to target_pose
Auto Trait Implementations
impl<T, I> RefUnwindSafe for RandomInitializeIkSolver<T, I> where
I: RefUnwindSafe,
T: RefUnwindSafe,
impl<T, I> Send for RandomInitializeIkSolver<T, I> where
I: Send,
impl<T, I> Sync for RandomInitializeIkSolver<T, I> where
I: Sync,
impl<T, I> Unpin for RandomInitializeIkSolver<T, I> where
I: Unpin,
T: Unpin,
impl<T, I> UnwindSafe for RandomInitializeIkSolver<T, I> where
I: UnwindSafe,
T: UnwindSafe,
Blanket Implementations
Mutably borrows from an owned value. Read more
impl<T> Downcast for T where
T: Any,
impl<T> Downcast for T where
T: 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
. Read more
pub fn into_any_rc(self: Rc<T>) -> Rc<dyn Any + 'static>
pub fn into_any_rc(self: Rc<T>) -> Rc<dyn Any + 'static>
Convert Rc<Trait>
(where Trait: Downcast
) to Rc<Any>
. Rc<Any>
can then be
further downcast
into Rc<ConcreteType>
where ConcreteType
implements Trait
. Read more
Convert &Trait
(where Trait: Downcast
) to &Any
. This is needed since Rust cannot
generate &Any
’s vtable from &Trait
’s. Read more
pub fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
pub 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. Read more
Instruments this type with the provided Span
, returning an
Instrumented
wrapper. Read more
type Output = T
type Output = T
Should always be Self
The inverse inclusion map: attempts to construct self
from the equivalent element of its
superset. Read more
pub fn is_in_subset(&self) -> bool
pub fn is_in_subset(&self) -> bool
Checks if self
is actually part of its subset T
(and can be converted to it).
pub fn to_subset_unchecked(&self) -> SS
pub fn to_subset_unchecked(&self) -> SS
Use with care! Same as self.to_subset
but without any property checks. Always succeeds.
pub fn from_subset(element: &SS) -> SP
pub fn from_subset(element: &SS) -> SP
The inclusion map: converts self
to the equivalent element of its superset.
pub fn vzip(self) -> V