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§
sourcefn solve_with_constraints(
&self,
arm: &SerialChain<T>,
target_pose: &Isometry<T, Unit<Quaternion<T>>, 3>,
constraints: &Constraints,
) -> Result<(), Error>
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§
sourcefn solve(
&self,
arm: &SerialChain<T>,
target_pose: &Isometry<T, Unit<Quaternion<T>>, 3>,
) -> Result<(), Error>
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