Struct rubullet::InverseKinematicsParametersBuilder [−][src]
pub struct InverseKinematicsParametersBuilder<'a> { /* fields omitted */ }
Expand description
creates InverseKinematicsParameters
using the Builder Pattern
which can then be used in calculate_inverse_kinematics()
.
Use the build() method to get the parameters.
const INITIAL_JOINT_POSITIONS: [f64; 9] = [0.98, 0.458, 0.31, -2.24, -0.30, 2.66, 2.32, 0.02, 0.02]; const PANDA_NUM_DOFS: usize = 7; const PANDA_END_EFFECTOR_INDEX: usize = 11; const LL: [f64; 9] = [-7.; 9]; // size is 9 = 7 DOF + 2 DOF for the gripper const UL: [f64; 9] = [7.; 9]; // size is 9 = 7 DOF + 2 DOF for the gripper const JR: [f64; 9] = [7.; 9]; // size is 9 = 7 DOF + 2 DOF for the gripper const NULL_SPACE_PARAMETERS: InverseKinematicsNullSpaceParameters<'static> = InverseKinematicsNullSpaceParameters { lower_limits: &LL, upper_limits: &UL, joint_ranges: &JR, rest_poses: &INITIAL_JOINT_POSITIONS, }; let inverse_kinematics_parameters = InverseKinematicsParametersBuilder::new( PANDA_END_EFFECTOR_INDEX, &Isometry3::translation(0.3,0.3,0.3), ) .set_max_num_iterations(5) .use_null_space(NULL_SPACE_PARAMETERS) .build();
Implementations
creates a new InverseKinematicsParametersBuilder
Arguments
end_effector_link_index
- end effector link indextarget_pose
- target pose of the end effector in its link coordinate (not CoM). useignore_orientation()
if you do not want to consider the orientation
Do not consider the orientation while calculating the IK
Consider the nullspace when calculating the IK
Allow to tune the IK solution using joint damping factors
Use a different IK-Solver. The default is DLS
Specify the current joint position if you do not want to use the position of the body. If you use it the target pose will be in local space!
Sets the maximum number of iterations. The default is 20.
Recalculate the IK until the distance between target and actual end effector is smaller than the residual threshold or max_num_iterations is reached.
creates the parameters
Auto Trait Implementations
impl<'a> RefUnwindSafe for InverseKinematicsParametersBuilder<'a>
impl<'a> Send for InverseKinematicsParametersBuilder<'a>
impl<'a> Sync for InverseKinematicsParametersBuilder<'a>
impl<'a> Unpin for InverseKinematicsParametersBuilder<'a>
impl<'a> UnwindSafe for InverseKinematicsParametersBuilder<'a>
Blanket Implementations
Mutably borrows from an owned value. 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