pub struct JointPathPlannerWithIk<T, I>where
    I: InverseKinematicsSolver<T>,
    T: RealField + Copy + 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§

source§

impl<T, I> JointPathPlannerWithIk<T, I>where T: RealField + SubsetOf<f64> + Float, I: InverseKinematicsSolver<T>,

source

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);
source

pub fn solve_ik( &mut self, arm: &SerialChain<T>, target_pose: &Isometry3<T> ) -> Result<(), Error>

Just solve IK and do not plan

source

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

source

pub fn plan_with_ik( &mut self, target_name: &str, target_pose: &Isometry3<T>, objects: &Compound<T> ) -> Result<Vec<Vec<T>>, Error>

Solve IK and get the path to the final joint positions

source

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

source

pub fn plan_joints<K>( &mut self, using_joint_names: &[String], start_angles: &[T], goal_angles: &[T], objects: &Compound<T> ) -> Result<Vec<Vec<T>>, Error>

Do not solve IK but get the path to the target joint positions

source

pub fn update_transforms(&self) -> Vec<Isometry3<T>>

Calculate the transforms of all of the links

source

pub fn joint_names(&self) -> Vec<String>

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§

source§

impl<T> Any for Twhere T: 'static + ?Sized,

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

impl<T> Borrow<T> for Twhere T: ?Sized,

const: unstable · source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

impl<T> BorrowMut<T> for Twhere T: ?Sized,

const: unstable · source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
§

impl<T> Downcast for Twhere T: Any,

§

fn into_any(self: Box<T, Global>) -> Box<dyn Any + 'static, Global>

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.
§

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.
§

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.
§

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.
§

impl<T> DowncastSync for Twhere T: Any + Send + Sync,

§

fn into_any_arc(self: Arc<T>) -> Arc<dyn Any + Sync + Send + 'static>

Convert Arc<Trait> (where Trait: Downcast) to Arc<Any>. Arc<Any> can then be further downcast into Arc<ConcreteType> where ConcreteType implements Trait.
source§

impl<T> From<T> for T

const: unstable · source§

fn from(t: T) -> T

Returns the argument unchanged.

source§

impl<T> Instrument for T

source§

fn instrument(self, span: Span) -> Instrumented<Self>

Instruments this type with the provided Span, returning an Instrumented wrapper. Read more
source§

fn in_current_span(self) -> Instrumented<Self>

Instruments this type with the current Span, returning an Instrumented wrapper. Read more
source§

impl<T, U> Into<U> for Twhere U: From<T>,

const: unstable · source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

§

impl<T> Pointable for T

§

const ALIGN: usize = mem::align_of::<T>()

The alignment of pointer.
§

type Init = T

The type for initializers.
§

unsafe fn init(init: <T as Pointable>::Init) -> usize

Initializes a with the given initializer. Read more
§

unsafe fn deref<'a>(ptr: usize) -> &'a T

Dereferences the given pointer. Read more
§

unsafe fn deref_mut<'a>(ptr: usize) -> &'a mut T

Mutably dereferences the given pointer. Read more
§

unsafe fn drop(ptr: usize)

Drops the object pointed to by the given pointer. Read more
source§

impl<T> Same<T> for T

§

type Output = T

Should always be Self
§

impl<SS, SP> SupersetOf<SS> for SPwhere SS: SubsetOf<SP>,

§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
source§

impl<T, U> TryFrom<U> for Twhere U: Into<T>,

§

type Error = Infallible

The type returned in the event of a conversion error.
const: unstable · source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
source§

impl<T, U> TryInto<U> for Twhere U: TryFrom<T>,

§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
const: unstable · source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
§

impl<V, T> VZip<V> for Twhere V: MultiLane<T>,

§

fn vzip(self) -> V

source§

impl<T> WithSubscriber for T

source§

fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>where S: Into<Dispatch>,

Attaches the provided Subscriber to this type, returning a WithDispatch wrapper. Read more
source§

fn with_current_subscriber(self) -> WithDispatch<Self>

Attaches the current default Subscriber to this type, returning a WithDispatch wrapper. Read more