Struct openrr_planner::JointPathPlannerWithIk
source · pub struct JointPathPlannerWithIk<T, I>{
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§
source§impl<T, I> JointPathPlannerWithIk<T, I>
impl<T, I> JointPathPlannerWithIk<T, I>
sourcepub fn new(path_planner: JointPathPlanner<T>, ik_solver: I) -> Self
pub fn new(path_planner: JointPathPlanner<T>, ik_solver: I) -> Self
Create instance from JointPathPlannerBuilder
and InverseKinematicsSolver
§Example
// Create path planner with loading urdf file and set end link name
let robot = k::Chain::from_urdf_file("sample.urdf").unwrap();
let planner = openrr_planner::JointPathPlannerBuilder::from_urdf_file("sample.urdf")
.unwrap()
.collision_check_margin(0.01)
.reference_robot(std::sync::Arc::new(robot))
.finalize()
.unwrap();
// Create inverse kinematics solver
let solver = openrr_planner::JacobianIkSolver::default();
// Create path planner with IK solver
let _planner = openrr_planner::JointPathPlannerWithIk::new(planner, solver);
sourcepub fn solve_ik(
&mut self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>,
) -> Result<()>
pub fn solve_ik( &mut self, arm: &SerialChain<T>, target_pose: &Isometry3<T>, ) -> Result<()>
Just solve IK and do not plan
sourcepub fn solve_ik_with_constraints(
&mut self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>,
c: &Constraints,
) -> Result<()>
pub fn solve_ik_with_constraints( &mut self, arm: &SerialChain<T>, target_pose: &Isometry3<T>, c: &Constraints, ) -> Result<()>
Just solve IK with constraints and do not plan
pub fn colliding_link_names(&self, objects: &Compound<T>) -> Vec<String>
sourcepub fn plan_with_ik(
&mut self,
target_name: &str,
target_pose: &Isometry3<T>,
objects: &Compound<T>,
) -> Result<Vec<Vec<T>>>
pub fn plan_with_ik( &mut self, target_name: &str, target_pose: &Isometry3<T>, objects: &Compound<T>, ) -> Result<Vec<Vec<T>>>
Solve IK and get the path to the final joint positions
sourcepub fn plan_with_ik_with_constraints(
&mut self,
target_name: &str,
target_pose: &Isometry3<T>,
objects: &Compound<T>,
constraints: &Constraints,
) -> Result<Vec<Vec<T>>>
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>>>
Solve IK with constraints and get the path to the final joint positions
sourcepub fn plan_joints<K>(
&mut self,
using_joint_names: &[String],
start_angles: &[T],
goal_angles: &[T],
objects: &Compound<T>,
) -> Result<Vec<Vec<T>>>
pub fn plan_joints<K>( &mut self, using_joint_names: &[String], start_angles: &[T], goal_angles: &[T], objects: &Compound<T>, ) -> Result<Vec<Vec<T>>>
Do not solve IK but get the path to the target joint positions
sourcepub fn update_transforms(&self) -> Vec<Isometry3<T>>
pub fn update_transforms(&self) -> Vec<Isometry3<T>>
Calculate the transforms of all of the links
sourcepub fn joint_names(&self) -> Vec<String>
pub fn joint_names(&self) -> Vec<String>
Get the names of the links
Auto Trait Implementations§
impl<T, I> Freeze for JointPathPlannerWithIk<T, I>
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>
impl<T, I> !UnwindSafe for JointPathPlannerWithIk<T, I>
Blanket Implementations§
source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more
source§impl<T> Downcast for Twhere
T: Any,
impl<T> Downcast for Twhere
T: Any,
source§fn into_any(self: Box<T>) -> Box<dyn Any>
fn into_any(self: Box<T>) -> Box<dyn 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
.source§fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>
fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>
Convert
Rc<Trait>
(where Trait: Downcast
) to Rc<Any>
. Rc<Any>
can then be
further downcast
into Rc<ConcreteType>
where ConcreteType
implements Trait
.source§fn as_any(&self) -> &(dyn Any + 'static)
fn as_any(&self) -> &(dyn Any + 'static)
Convert
&Trait
(where Trait: Downcast
) to &Any
. This is needed since Rust cannot
generate &Any
’s vtable from &Trait
’s.source§fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
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.source§impl<T> DowncastSync for T
impl<T> DowncastSync for T
source§impl<T> Instrument for T
impl<T> Instrument for T
source§fn instrument(self, span: Span) -> Instrumented<Self>
fn instrument(self, span: Span) -> Instrumented<Self>
source§fn in_current_span(self) -> Instrumented<Self>
fn in_current_span(self) -> Instrumented<Self>
source§impl<T> IntoEither for T
impl<T> IntoEither for T
source§fn into_either(self, into_left: bool) -> Either<Self, Self>
fn into_either(self, into_left: bool) -> Either<Self, Self>
Converts
self
into a Left
variant of Either<Self, Self>
if into_left
is true
.
Converts self
into a Right
variant of Either<Self, Self>
otherwise. Read moresource§fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
Converts
self
into a Left
variant of Either<Self, Self>
if into_left(&self)
returns true
.
Converts self
into a Right
variant of Either<Self, Self>
otherwise. Read moresource§impl<T> Pointable for T
impl<T> Pointable for T
source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
The inverse inclusion map: attempts to construct
self
from the equivalent element of its
superset. Read moresource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
Checks if
self
is actually part of its subset T
(and can be converted to it).source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
Use with care! Same as
self.to_subset
but without any property checks. Always succeeds.source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
The inclusion map: converts
self
to the equivalent element of its superset.