Crate gear [] [src]

Motion Planning Library for Robotics

Get the collision free trajectory of joint angles. ncollide is used to check the collision between the robot and the environment.

Example

extern crate gear;
extern crate nalgebra as na;
extern crate ncollide;

use ncollide::shape::{Compound3, Cuboid, ShapeHandle3};

fn main() {
    // Create path planner with loading urdf file and set end link name
    let planner = gear::JointPathPlannerBuilder::try_from_urdf_file("sample.urdf", "l_wrist2")
        .unwrap()
        .collision_check_margin(0.01)
        .finalize();
    // Create inverse kinematics solver
    let solver = gear::JacobianIKSolverBuilder::<f64>::new()
        .num_max_try(1000)
        .allowable_target_distance(0.01)
        .move_epsilon(0.00001)
        .jacobian_move_epsilon(0.001)
        .finalize();
    let solver = gear::RandomInitializeIKSolver::new(solver, 100);
    // Create path planner with IK solver
    let mut planner = gear::JointPathPlannerWithIK::new(planner, solver);

    // Create obstacles, or use `gear::create_compound_from_urdf("obstacles.urdf")`
    let obstacle_shape1 = ShapeHandle3::new(Cuboid::new(na::Vector3::new(0.20, 0.4, 0.1)));
    let obstacle_pose1 = na::Isometry3::new(na::Vector3::new(0.7, 0.0, 0.1), na::zero());

    let obstacle_shape2 = ShapeHandle3::new(Cuboid::new(na::Vector3::new(0.20, 0.3, 0.1)));
    let obstacle_pose2 = na::Isometry3::new(na::Vector3::new(0.7, 0.0, 0.6), na::zero());

    let obstacles = Compound3::new(vec![
        (obstacle_pose1, obstacle_shape1),
        (obstacle_pose2, obstacle_shape2),
    ]);

    // Set IK target transformation
    let mut ik_target_pose = na::Isometry3::from_parts(
        na::Translation3::new(0.40, 0.20, 0.3),
        na::UnitQuaternion::from_euler_angles(0.0, -0.1, 0.0),
    );
    // Plan the path, path is the vector of joint angles for root to "l_wrist2"
    let plan1 = planner.plan_with_ik(&ik_target_pose, &obstacles).unwrap();
    println!("plan1 = {:?}", plan1);
    ik_target_pose.translation.vector[2] += 0.50;
    // plan the path from previous result
    let plan2 = planner.plan_with_ik(&ik_target_pose, &obstacles).unwrap();
    println!("plan2 = {:?}", plan2);
}

Structs

CollisionChecker

Collision checker for a robot

JacobianIKSolver

Inverse Kinematics Solver using Jacobian matrix

JacobianIKSolverBuilder

Build jacobianIKSolverBuilder

JointPathPlanner

Collision Avoidance Path Planner

JointPathPlannerBuilder

Builder pattern to create JointPathPlanner

JointPathPlannerWithIK

Joint path planner which supports inverse kinematics

RandomInitializeIKSolver

Randomize initial joint angles before solving

Enums

Error

Error for gear

Traits

InverseKinematicsSolver

IK solver

Functions

create_compound_from_urdf

Create ncollide::shape::Compound3 from URDF file

create_compound_from_urdf_robot

Create ncollide::shape::Compound3 from urdf_rs::Robot

generate_clamped_joint_angles_from_limits

Clamp joint angles to set angles safely

generate_random_joint_angles_from_limits

Generate random joint angles from the optional limits

interpolate

Interpolate two vectors with the length

modify_to_nearest_angle

Find the nearest angle on is for the joints wihout limits

set_random_joint_angles

Set random joint angles

Type Definitions

DefaultJointPathPlanner
DefaultJointPathPlannerBuilder
Result

Result for gear