Collision Avoidance Path Planning for robotics in Rust-lang
```rust extern crate gear; extern crate nalgebra as na;
fn main() {
// Create path planner with loading urdf file and set end link name
let planner = gear::JointPathPlannerBuilder::tryfromurdffile("sample.urdf", "lwrist2")
.expect("failed to create planner from urdf file")
.collisioncheckmargin(0.01)
.finalize();
// Create inverse kinematics solver
let solver = gear::JacobianIKSolverBuilder::
// Create obstacles
let obstacles =
gear::create_compound_from_urdf("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 "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);
} ```
bash
cargo run --release --example reach
f
/b
to move IK targettype g
to move the end of the arm to the target
type i
to just solve inverse kinematics for the target
r
to set random posec
to check collisionThe example can handle any urdf files (sample.urdf is used as default). It requires the name of the target end link name.
bash
cargo run --release --example reach YOUR_URDF_FILE_PATH END_LINK_NAME
For example,
bash
cargo run --release --example reach $(rospack find pr2_description)/robots/pr2.urdf.xacro l_gripper_palm_link
bash
cargo run --release --example reach $(rospack find ur_description)/urdf/ur10_robot.urdf.xacro ee_link
bash
cargo run --release --example reach $(rospack find sawyer_description)/urdf/sawyer.urdf right_hand