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
moving_arm: K
Instance of k::JointContainer
to set joint angles
collision_check_robot: R
Instance of k::LinkContainer
to check the collision
collision_checker: CollisionChecker<f64>
Collision checker
step_length: f64
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
Methods
impl<K, R> JointPathPlanner<K, R> where
K: JointContainer<f64>,
R: LinkContainer<f64>,
[src]
K: JointContainer<f64>,
R: LinkContainer<f64>,
fn new(
moving_arm: K,
collision_check_robot: R,
collision_checker: CollisionChecker<f64>,
step_length: f64,
max_try: usize,
num_smoothing: usize
) -> Self
[src]
moving_arm: K,
collision_check_robot: R,
collision_checker: CollisionChecker<f64>,
step_length: f64,
max_try: usize,
num_smoothing: usize
) -> Self
Create JointPathPlanner
fn is_feasible(
&mut self,
joint_angles: &[f64],
objects: &Compound3<f64>
) -> bool
[src]
&mut self,
joint_angles: &[f64],
objects: &Compound3<f64>
) -> bool
Check if the joint_angles are OK
fn has_any_colliding(&self, objects: &Compound3<f64>) -> bool
[src]
Check if there are any colliding links
fn get_colliding_link_names(&self, objects: &Compound3<f64>) -> Vec<String>
[src]
Get the names of colliding links
fn plan(
&mut self,
start_angles: &[f64],
goal_angles: &[f64],
objects: &Compound3<f64>
) -> Result<Vec<Vec<f64>>>
[src]
&mut self,
start_angles: &[f64],
goal_angles: &[f64],
objects: &Compound3<f64>
) -> Result<Vec<Vec<f64>>>
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
andobjects
will be checked.
Trait Implementations
impl<K, R> JointContainer<f64> for JointPathPlanner<K, R> where
K: JointContainer<f64>,
R: LinkContainer<f64>,
[src]
K: JointContainer<f64>,
R: LinkContainer<f64>,
fn set_joint_angles(&mut self, joint_angles: &[f64]) -> Result<(), JointError>
[src]
Set the joint angles of self.moving_arm
fn get_joint_angles(&self) -> Vec<f64>
[src]
Get the joint angles of self.moving_arm
fn get_joint_limits(&self) -> Vec<Option<Range<f64>>>
[src]
Get the limits of the joints, if it exists.
fn get_joint_names(&self) -> Vec<String>
[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]
K: JointContainer<f64>,
R: LinkContainer<f64>,
fn calc_link_transforms(&self) -> Vec<Isometry3<f64>>
[src]
Calculate the transforms of all of the links
fn get_link_names(&self) -> Vec<String>
[src]
Get the names of the links