Struct openrr_planner::JointPathPlannerWithIk [−][src]
pub struct JointPathPlannerWithIk<T, I> where
I: InverseKinematicsSolver<T>,
T: RealField + SubsetOf<f64>, { pub path_planner: JointPathPlanner<T>, pub ik_solver: I, }
Expand description
Joint path planner which supports inverse kinematics
Fields
path_planner: JointPathPlanner<T>
Joint Path Planner to be used to find collision free path
Currently, JointPathPlanner<N, k::Chain<N>>
is used.
ik_solver: I
Inverse kinematics solver to find the goal joint angles
Implementations
impl<T, I> JointPathPlannerWithIk<T, I> where
T: RealField + SubsetOf<f64> + Float,
I: InverseKinematicsSolver<T>,
impl<T, I> JointPathPlannerWithIk<T, I> where
T: RealField + SubsetOf<f64> + Float,
I: InverseKinematicsSolver<T>,
Create instance from JointPathPlannerBuilder
and InverseKinematicsSolver
Example
// Create path planner with loading urdf file and set end link name let planner = openrr_planner::JointPathPlannerBuilder::from_urdf_file("sample.urdf") .unwrap() .collision_check_margin(0.01) .finalize(); // Create inverse kinematics solver let solver = openrr_planner::JacobianIkSolver::default(); // Create path planner with IK solver let _planner = openrr_planner::JointPathPlannerWithIk::new(planner, solver);
Just solve IK and do not plan
pub fn solve_ik_with_constraints(
&mut self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>,
c: &Constraints
) -> Result<(), Error>
pub fn solve_ik_with_constraints(
&mut self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>,
c: &Constraints
) -> Result<(), Error>
Just solve IK with constraints and do not plan
Solve IK and get the path to the final joint positions
pub fn plan_with_ik_with_constraints(
&mut self,
target_name: &str,
target_pose: &Isometry3<T>,
objects: &Compound<T>,
constraints: &Constraints
) -> Result<Vec<Vec<T>>, Error>
pub fn plan_with_ik_with_constraints(
&mut self,
target_name: &str,
target_pose: &Isometry3<T>,
objects: &Compound<T>,
constraints: &Constraints
) -> Result<Vec<Vec<T>>, Error>
Solve IK with constraints and get the path to the final joint positions
Do not solve IK but get the path to the target joint positions
Calculate the transforms of all of the links
Get the names of the links
Auto Trait Implementations
impl<T, I> !RefUnwindSafe for JointPathPlannerWithIk<T, I>
impl<T, I> Send for JointPathPlannerWithIk<T, I> where
I: Send,
impl<T, I> Sync for JointPathPlannerWithIk<T, I> where
I: Sync,
impl<T, I> Unpin for JointPathPlannerWithIk<T, I> where
I: Unpin,
T: Unpin,
impl<T, I> !UnwindSafe for JointPathPlannerWithIk<T, I>
Blanket Implementations
Mutably borrows from an owned value. Read more
impl<T> Downcast for T where
T: Any,
impl<T> Downcast for T where
T: Any,
Convert Box<dyn Trait>
(where Trait: Downcast
) to Box<dyn Any>
. Box<dyn Any>
can
then be further downcast
into Box<ConcreteType>
where ConcreteType
implements Trait
. Read more
pub fn into_any_rc(self: Rc<T>) -> Rc<dyn Any + 'static>
pub fn into_any_rc(self: Rc<T>) -> Rc<dyn Any + 'static>
Convert Rc<Trait>
(where Trait: Downcast
) to Rc<Any>
. Rc<Any>
can then be
further downcast
into Rc<ConcreteType>
where ConcreteType
implements Trait
. Read more
Convert &Trait
(where Trait: Downcast
) to &Any
. This is needed since Rust cannot
generate &Any
’s vtable from &Trait
’s. Read more
pub fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
pub fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
Convert &mut Trait
(where Trait: Downcast
) to &Any
. This is needed since Rust cannot
generate &mut Any
’s vtable from &mut Trait
’s. Read more
Instruments this type with the provided Span
, returning an
Instrumented
wrapper. 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