Struct gear::JointPathPlannerWithIK
[−]
[src]
pub struct JointPathPlannerWithIK<K> where
K: InverseKinematicsSolver<f64>, { pub path_planner: DefaultJointPathPlanner<f64>, pub ik_solver: K, }
Joint path planner which supports inverse kinematics
Fields
path_planner: DefaultJointPathPlanner<f64>
Joint Path Planner to be used to find collision free path
Currently, JointPathPlanner<k::RcKinematicChain<f64>, k::LinkTree<f64>>
is used.
ik_solver: K
Inverse kinematics solver to find the goal joint angles
Methods
impl<K> JointPathPlannerWithIK<K> where
K: InverseKinematicsSolver<f64>,
[src]
K: InverseKinematicsSolver<f64>,
fn new(path_planner: DefaultJointPathPlanner<f64>, ik_solver: K) -> Self
[src]
Create instance from JointPathPlannerBuilder
and InverseKinematicsSolver
Example
// Create path planner with loading urdf file and set end link name let planner = gear::JointPathPlannerBuilder::try_from_urdf_file("sample.urdf", "l_wrist2") .unwrap() .collision_check_margin(0.01) .finalize(); // Create inverse kinematics solver let solver = gear::JacobianIKSolverBuilder::<f64>::new() .num_max_try(1000) .allowable_target_distance(0.01) .move_epsilon(0.00001) .jacobian_move_epsilon(0.001) .finalize(); // Create path planner with IK solver let _planner = gear::JointPathPlannerWithIK::new(planner, solver);
fn urdf_robot(&self) -> &Option<Robot>
[src]
fn solve_ik(&mut self, target_pose: &Isometry3<f64>) -> Result<f64>
[src]
fn get_colliding_link_names(&self, objects: &Compound3<f64>) -> Vec<String>
[src]
fn plan_with_ik(
&mut self,
target_pose: &Isometry3<f64>,
objects: &Compound3<f64>
) -> Result<Vec<Vec<f64>>>
[src]
&mut self,
target_pose: &Isometry3<f64>,
objects: &Compound3<f64>
) -> Result<Vec<Vec<f64>>>
fn plan_joints(
&mut self,
start_angles: &[f64],
goal_angles: &[f64],
objects: &Compound3<f64>
) -> Result<Vec<Vec<f64>>>
[src]
&mut self,
start_angles: &[f64],
goal_angles: &[f64],
objects: &Compound3<f64>
) -> Result<Vec<Vec<f64>>>
Trait Implementations
impl<K> JointContainer<f64> for JointPathPlannerWithIK<K> where
K: InverseKinematicsSolver<f64>,
[src]
K: InverseKinematicsSolver<f64>,
fn set_joint_angles(&mut self, joint_angles: &[f64]) -> Result<(), JointError>
[src]
Set the angles of the joints Read more
fn get_joint_angles(&self) -> Vec<f64>
[src]
Get the angles of the joints
fn get_joint_limits(&self) -> Vec<Option<Range<f64>>>
[src]
Get the limits of the joints, if it exists.
fn get_joint_names(&self) -> Vec<String>
[src]
Get the all names of the joints
impl<K> LinkContainer<f64> for JointPathPlannerWithIK<K> where
K: InverseKinematicsSolver<f64>,
[src]
K: InverseKinematicsSolver<f64>,
fn calc_link_transforms(&self) -> Vec<Isometry3<f64>>
[src]
Calculate the transforms of all of the links
fn get_link_names(&self) -> Vec<String>
[src]
Get the names of the links