Struct gear::JointPathPlanner [] [src]

pub struct JointPathPlanner<K, R> where
    K: JointContainer<f64>,
    R: LinkContainer<f64>, 
{ pub moving_arm: K, pub collision_check_robot: R, pub collision_checker: CollisionChecker<f64>, pub step_length: f64, pub max_try: usize, pub num_smoothing: usize, pub urdf_robot: Option<Robot>, }

Collision Avoidance Path Planner

Fields

Instance of k::JointContainer to set joint angles

Instance of k::LinkContainer to check the collision

Collision checker

Unit length for searching

If the value is large, the path become sparse.

Max num of RRT search loop

Num of path smoothing trials

The robot instance which is used to create the robot model

Methods

impl<K, R> JointPathPlanner<K, R> where
    K: JointContainer<f64>,
    R: LinkContainer<f64>, 
[src]

[src]

Create JointPathPlanner

[src]

Check if the joint_angles are OK

[src]

Check if there are any colliding links

Get the names of colliding links

[src]

Plan the sequence of joint angles of self.moving_arm

Arguments

  • start_angles: initial joint angles of self.moving_arm.
  • goal_angles: goal joint angles of self.moving_arm.
  • objects: The collision between self.collision_check_robot and objects will be checked.

Trait Implementations

impl<K, R> JointContainer<f64> for JointPathPlanner<K, R> where
    K: JointContainer<f64>,
    R: LinkContainer<f64>, 
[src]

[src]

Set the joint angles of self.moving_arm

[src]

Get the joint angles of self.moving_arm

[src]

Get the limits of the joints, if it exists.

[src]

Get the all names of the joints

impl<K, R> LinkContainer<f64> for JointPathPlanner<K, R> where
    K: JointContainer<f64>,
    R: LinkContainer<f64>, 
[src]

Calculate the transforms of all of the links

Get the names of the links