[−][src]Struct gear::JointPathPlanner
Collision Avoidance Path Planner
Fields
collision_check_robot: Chain<N>
Instance of k::HasLinks
to check the collision
collision_checker: CollisionChecker<N>
Collision checker
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
urdf_robot: Option<Robot>
The robot instance which is used to create the robot model
self_collision_pairs: Vec<(String, String)>
Optional self collision check node names
Implementations
impl<N> JointPathPlanner<N> where
N: RealField + Float + SubsetOf<f64>,
[src]
N: RealField + Float + SubsetOf<f64>,
pub fn new(
collision_check_robot: Chain<N>,
collision_checker: CollisionChecker<N>,
step_length: N,
max_try: usize,
num_smoothing: usize
) -> Self
[src]
collision_check_robot: Chain<N>,
collision_checker: CollisionChecker<N>,
step_length: N,
max_try: usize,
num_smoothing: usize
) -> Self
Create JointPathPlanner
pub fn is_feasible(
&self,
using_joints: &Chain<N>,
joint_positions: &[N],
objects: &Compound<N>
) -> bool
[src]
&self,
using_joints: &Chain<N>,
joint_positions: &[N],
objects: &Compound<N>
) -> bool
Check if the joint_positions are OK
pub fn has_any_colliding(&self, objects: &Compound<N>) -> bool
[src]
Check if there are any colliding links
pub fn colliding_link_names(&self, objects: &Compound<N>) -> Vec<String>
[src]
Get the names of colliding links
pub fn is_feasible_with_self(
&self,
using_joints: &Chain<N>,
joint_positions: &[N]
) -> bool
[src]
&self,
using_joints: &Chain<N>,
joint_positions: &[N]
) -> bool
Check if the joint_positions are OK
pub fn has_any_colliding_with_self(&self) -> bool
[src]
Check if there are any colliding links
pub fn colliding_link_names_with_self(&self) -> Vec<(String, String)>
[src]
Get the names of colliding links
pub fn plan(
&self,
using_joints: &Chain<N>,
start_angles: &[N],
goal_angles: &[N],
objects: &Compound<N>
) -> Result<Vec<Vec<N>>, Error>
[src]
&self,
using_joints: &Chain<N>,
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 ofusing_joints
.goal_angles
: goal joint angles ofusing_joints
.objects
: The collision betweenself.collision_check_robot
andobjects
will be checked.
pub fn plan_avoid_self_collision(
&self,
using_joints: &Chain<N>,
start_angles: &[N],
goal_angles: &[N]
) -> Result<Vec<Vec<N>>, Error>
[src]
&self,
using_joints: &Chain<N>,
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 ofusing_joints
.goal_angles
: goal joint angles ofusing_joints
.
pub fn update_transforms(&self) -> Vec<Isometry3<N>>
[src]
Calculate the transforms of all of the links
pub fn joint_names(&self) -> Vec<String>
[src]
Get the names of the links
Auto Trait Implementations
impl<N> !RefUnwindSafe for JointPathPlanner<N>
[src]
impl<N> Send for JointPathPlanner<N> where
N: Scalar,
[src]
N: Scalar,
impl<N> Sync for JointPathPlanner<N> where
N: Scalar,
[src]
N: Scalar,
impl<N> Unpin for JointPathPlanner<N> where
N: Scalar + Unpin,
[src]
N: Scalar + Unpin,
impl<N> !UnwindSafe for JointPathPlanner<N>
[src]
Blanket Implementations
impl<T> Any for T where
T: 'static + ?Sized,
[src]
T: 'static + ?Sized,
impl<T> Borrow<T> for T where
T: ?Sized,
[src]
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
[src]
T: ?Sized,
pub fn borrow_mut(&mut self) -> &mut T
[src]
impl<T> Downcast for T where
T: Any,
T: Any,
pub fn into_any(self: Box<T, Global>) -> Box<dyn Any + 'static, Global>
pub fn into_any_rc(self: Rc<T>) -> Rc<dyn Any + 'static>
pub fn as_any(&self) -> &(dyn Any + 'static)
pub fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
impl<T> DowncastSync for T where
T: Send + Sync + Any,
T: Send + Sync + Any,
impl<T> From<T> for T
[src]
impl<T, U> Into<U> for T where
U: From<T>,
[src]
U: From<T>,
impl<T> Same<T> for T
type Output = T
Should always be Self
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
SS: SubsetOf<SP>,
pub fn to_subset(&self) -> Option<SS>
pub fn is_in_subset(&self) -> bool
pub fn to_subset_unchecked(&self) -> SS
pub fn from_subset(element: &SS) -> SP
impl<T, U> TryFrom<U> for T where
U: Into<T>,
[src]
U: Into<T>,
type Error = Infallible
The type returned in the event of a conversion error.
pub fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>
[src]
impl<T, U> TryInto<U> for T where
U: TryFrom<T>,
[src]
U: TryFrom<T>,
type Error = <U as TryFrom<T>>::Error
The type returned in the event of a conversion error.
pub fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>
[src]
impl<V, T> VZip<V> for T where
V: MultiLane<T>,
V: MultiLane<T>,