pub struct JointPathPlanner<N>where
    N: RealField + Copy + SubsetOf<f64>,{
    pub step_length: N,
    pub max_try: usize,
    pub num_smoothing: usize,
    /* private fields */
}
Expand description

Collision Avoidance Path Planner

Fields§

§step_length: N

Unit length for searching

If the value is large, the path become sparse.

§max_try: usize

Max num of RRT search loop

§num_smoothing: usize

Num of path smoothing trials

Implementations§

source§

impl<N> JointPathPlanner<N>where N: RealField + Float + SubsetOf<f64>,

source

pub fn new( reference_robot: Arc<Chain<N>>, robot_collision_detector: RobotCollisionDetector<N>, step_length: N, max_try: usize, num_smoothing: usize ) -> Self

Create JointPathPlanner

source

pub fn plan( &self, using_joint_names: &[String], start_angles: &[N], goal_angles: &[N], objects: &Compound<N> ) -> Result<Vec<Vec<N>>, Error>

Plan the sequence of joint angles of using_joints

Arguments
  • using_joints: part of collision_check_robot. the dof of the following angles must be same as this model.
  • start_angles: initial joint angles of using_joints.
  • goal_angles: goal joint angles of using_joints.
  • objects: The collision between self.collision_check_robot and objects will be checked.
source

pub fn plan_avoid_self_collision( &self, using_joint_names: &[String], start_angles: &[N], goal_angles: &[N] ) -> Result<Vec<Vec<N>>, Error>

Plan the sequence of joint angles of using_joints to avoid self collision.

Arguments
  • using_joints: part of collision_check_robot. the dof of the following angles must be same as this model.
  • start_angles: initial joint angles of using_joints.
  • goal_angles: goal joint angles of using_joints.
source

pub fn sync_joint_positions_with_reference(&self)

Synchronize joint positions of the planning robot model with the reference robot

source

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

Calculate the transforms of all of the links

source

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

Get the names of the links

source

pub fn collision_check_robot(&self) -> &Chain<N>

Get the robot model used for collision checking

Get names of links colliding with environmental objects objects: environmental objects

Get names of self-colliding links

Auto Trait Implementations§

§

impl<N> !RefUnwindSafe for JointPathPlanner<N>

§

impl<N> Send for JointPathPlanner<N>

§

impl<N> Sync for JointPathPlanner<N>

§

impl<N> Unpin for JointPathPlanner<N>where N: Unpin,

§

impl<N> !UnwindSafe for JointPathPlanner<N>

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