Crate openrr_planner

Source
Expand description

§OpenRR Planner

crates.io docs docs

Collision Avoidance Path Planning for robotics in Rust-lang. This starts as a copy of gear crate.

Video

Documents

§Code example

§minimum code example

use std::{path::Path, sync::Arc};

use k::nalgebra as na;
use ncollide3d::shape::Compound;
use openrr_planner::FromUrdf;

fn main() {
    let urdf_path = Path::new("sample.urdf");
    let robot = Arc::new(k::Chain::from_urdf_file(urdf_path).unwrap());

    // Create path planner with loading urdf file and set end link name
    let planner = openrr_planner::JointPathPlannerBuilder::from_urdf_file(urdf_path)
        .expect("failed to create planner from urdf file")
        .collision_check_margin(0.01)
        .reference_robot(robot.clone())
        .finalize()
        .unwrap();
    // Create inverse kinematics solver
    let solver = openrr_planner::JacobianIkSolver::default();
    let solver = openrr_planner::RandomInitializeIkSolver::new(solver, 100);
    // Create path planner with IK solver
    let mut planner = openrr_planner::JointPathPlannerWithIk::new(planner, solver);
    let target_name = "l_tool_fixed";
    // Create obstacles
    let obstacles = Compound::from_urdf_file("obstacles.urdf").expect("obstacle file not found");

    // 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 target_name
    let plan1 = planner
        .plan_with_ik(target_name, &ik_target_pose, &obstacles)
        .unwrap();
    println!("plan1 = {plan1:?}");

    // Apply plan1 to the reference robot (regarded as the real robot)
    let arm = k::Chain::from_end(robot.find(target_name).unwrap());
    arm.set_joint_positions_clamped(plan1.iter().last().unwrap());

    // Plan the path from previous result
    ik_target_pose.translation.vector[2] += 0.50;
    let plan2 = planner
        .plan_with_ik(target_name, &ik_target_pose, &obstacles)
        .unwrap();
    println!("plan2 = {plan2:?}");
}

§Run example with GUI

§How to run

cargo run --release --example reach

§GUI control

  • Up/Down/Left/Right/f/b to translate IK target
  • Shift + Up/Down/Left/Right/f/b to rotate IK target
  • type g to move the end of the arm to the target
  • type i to just solve inverse kinematics for the target without collision check
  • type r to set random pose
  • type c to check collision
  • type v to toggle shown element collision<->visual

§Use your robot

The example can handle any urdf files (sample.urdf is used as default). It requires the name of the target end link name.

cargo run --release --example reach YOUR_URDF_FILE_PATH END_LINK_NAME

For example,

§PR2
cargo run --release --example reach $(rospack find pr2_description)/robots/pr2.urdf.xacro l_gripper_palm_link

Video

§Universal Robot: UR10
cargo run --release --example reach $(rospack find ur_description)/urdf/ur10_robot.urdf.xacro ee_link

Sawyer movie

§Sawyer
cargo run --release --example reach $(rospack find sawyer_description)/urdf/sawyer.urdf right_hand

UR5 movie

§License

Licensed under the Apache License, Version 2.0.

Re-exports§

pub use crate::collision::CollisionDetector;
pub use crate::collision::FromUrdf;
pub use crate::collision::SelfCollisionChecker;
pub use crate::collision::SelfCollisionCheckerConfig;

Modules§

collision

Structs§

JacobianIkSolver
Inverse Kinematics Solver using Jacobian matrix
JointPathPlanner
Collision Avoidance Path Planner
JointPathPlannerBuilder
Builder pattern to create JointPathPlanner
JointPathPlannerConfig
JointPathPlannerWithIk
Joint path planner which supports inverse kinematics
RandomInitializeIkSolver
Randomize initial joint angles before solving
TrajectoryPoint
Struct for a point of a trajectory with multiple dimensions.

Enums§

Error
Error for openrr_planner

Traits§

InverseKinematicsSolver
IK solver

Functions§

create_chain_from_joint_names
Create a sub-chain of the collision check model by a name list
create_joint_path_planner
generate_clamped_joint_positions_from_limits
Clamp joint angles to set angles safely
generate_random_joint_positions_from_limits
Generate random joint angles from the optional limits
get_reachable_region
Check the poses which can be reached by the robot arm
interpolate
Interpolate position vectors
modify_to_nearest_angle
If the joint has no limit, select the nearest value from (x + 2pi *).
set_clamped_joint_positionsDeprecated
Set joint positions safely
set_random_joint_positions
Set random joint angles

Type Aliases§

Result
Result for openrr_planner