[−][src]Struct k::JacobianIKSolver
Inverse Kinematics Solver using Jacobian matrix
Fields
allowable_target_distance: T
If the distance is smaller than this value, it is reached.
allowable_target_angle: T
If the angle distance is smaller than this value, it is reached.
jacobian_multiplier: T
multiplier for jacobian
num_max_try: usize
How many times the joints are tried to be moved
Methods
impl<T> JacobianIKSolver<T> where
T: RealField,
[src]
T: RealField,
pub fn new(
allowable_target_distance: T,
allowable_target_angle: T,
jacobian_multiplier: T,
num_max_try: usize
) -> JacobianIKSolver<T>
[src]
allowable_target_distance: T,
allowable_target_angle: T,
jacobian_multiplier: T,
num_max_try: usize
) -> JacobianIKSolver<T>
Create instance of JacobianIKSolver
.
JacobianIKSolverBuilder
is available instead of calling this new
method.
Examples
let solver = k::JacobianIKSolver::new(0.01, 0.01, 0.5, 100);
Trait Implementations
impl<T> InverseKinematicsSolver<T> for JacobianIKSolver<T> where
T: RealField,
[src]
T: RealField,
fn solve(
&self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>
) -> Result<(), IKError>
[src]
&self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>
) -> Result<(), IKError>
Set joint positions of arm
to reach the target_pose
Examples
use k::prelude::*; let chain = k::Chain::<f32>::from_urdf_file("urdf/sample.urdf").unwrap(); // Create sub-`Chain` to make it easy to use inverse kinematics let target_joint_name = "r_wrist_pitch"; let r_wrist = chain.find(target_joint_name).unwrap(); let mut arm = k::SerialChain::from_end(r_wrist); println!("arm: {}", arm); // Set joint positions of `arm` let positions = vec![0.1, 0.2, 0.0, -0.5, 0.0, -0.3]; arm.set_joint_positions(&positions).unwrap(); println!("initial positions={:?}", arm.joint_positions()); // Get the transform of the end of the manipulator (forward kinematics) let mut target = arm.update_transforms().last().unwrap().clone(); println!("initial target pos = {}", target.translation); println!("move x: -0.1"); target.translation.vector.x -= 0.1; // Create IK solver with default settings let solver = k::JacobianIKSolver::default(); // solve and move the manipulator positions solver.solve(&arm, &target).unwrap(); println!("solved positions={:?}", arm.joint_positions());
fn solve_with_constraints(
&self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>,
constraints: &Constraints
) -> Result<(), IKError>
[src]
&self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>,
constraints: &Constraints
) -> Result<(), IKError>
impl<T: Clone + RealField> Clone for JacobianIKSolver<T>
[src]
fn clone(&self) -> JacobianIKSolver<T>
[src]
fn clone_from(&mut self, source: &Self)
1.0.0[src]
Performs copy-assignment from source
. Read more
impl<T> Default for JacobianIKSolver<T> where
T: RealField,
[src]
T: RealField,
impl<T: Debug + RealField> Debug for JacobianIKSolver<T>
[src]
Auto Trait Implementations
impl<T> Send for JacobianIKSolver<T>
impl<T> Sync for JacobianIKSolver<T>
Blanket Implementations
impl<T> ToOwned for T where
T: Clone,
[src]
T: Clone,
type Owned = T
The resulting type after obtaining ownership.
fn to_owned(&self) -> T
[src]
fn clone_into(&self, target: &mut T)
[src]
impl<T, U> Into<U> for T where
U: From<T>,
[src]
U: From<T>,
impl<T> From<T> for T
[src]
impl<T, U> TryFrom<U> for T where
U: Into<T>,
[src]
U: Into<T>,
type Error = Infallible
The type returned in the event of a conversion error.
fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>
[src]
impl<T, U> TryInto<U> for T where
U: TryFrom<T>,
[src]
U: TryFrom<T>,
type Error = <U as TryFrom<T>>::Error
The type returned in the event of a conversion error.
fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>
[src]
impl<T> BorrowMut<T> for T where
T: ?Sized,
[src]
T: ?Sized,
fn borrow_mut(&mut self) -> &mut T
[src]
impl<T> Borrow<T> for T where
T: ?Sized,
[src]
T: ?Sized,
impl<T> Any for T where
T: 'static + ?Sized,
[src]
T: 'static + ?Sized,
impl<T> Same<T> for T
type Output = T
Should always be Self
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
SS: SubsetOf<SP>,