pub trait InverseKinematicsSolver<T>where
    T: RealField,{
    // Required method
    fn solve_with_constraints(
        &self,
        arm: &SerialChain<T>,
        target_pose: &Isometry<T, Unit<Quaternion<T>>, 3>,
        constraints: &Constraints
    ) -> Result<(), Error>;

    // Provided method
    fn solve(
        &self,
        arm: &SerialChain<T>,
        target_pose: &Isometry<T, Unit<Quaternion<T>>, 3>
    ) -> Result<(), Error> { ... }
}
Expand description

IK solver

Required Methods§

source

fn solve_with_constraints( &self, arm: &SerialChain<T>, target_pose: &Isometry<T, Unit<Quaternion<T>>, 3>, constraints: &Constraints ) -> Result<(), Error>

Move the end transform of the arm to target_pose with constraints

Provided Methods§

source

fn solve( &self, arm: &SerialChain<T>, target_pose: &Isometry<T, Unit<Quaternion<T>>, 3> ) -> Result<(), Error>

Move the end transform of the arm to target_pose

Implementors§

source§

impl<T> InverseKinematicsSolver<T> for JacobianIkSolver<T>where T: RealField + SubsetOf<f64>,

source§

impl<T, I> InverseKinematicsSolver<T> for RandomInitializeIkSolver<T, I>where T: RealField + Copy + SubsetOf<f64>, I: InverseKinematicsSolver<T>,