pub fn load_trimesh_from_stl(stl_file_path: &str) -> TriMesh
Expand description
Function to load a TriMesh from an STL file
Examples found in repository?
examples/path_planning_rrt.rs (line 19)
16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67
pub fn create_rx160_robot() -> KinematicsWithShape {
use rs_opw_kinematics::read_trimesh::load_trimesh_from_stl;
let monolith = load_trimesh_from_stl("src/tests/data/object.stl");
KinematicsWithShape::new(
Parameters {
a1: 0.15,
a2: 0.0,
b: 0.0,
c1: 0.55,
c2: 0.825,
c3: 0.625,
c4: 0.11,
..Parameters::new()
},
// Constraints are used also to sample constraint-compliant random positions
// as needed by this path planner.
Constraints::from_degrees(
[
-225.0..=225.0, -225.0..=225.0, -225.0..=225.0,
-225.0..=225.0, -225.0..=225.0, -225.0..=225.0,
],
BY_PREV,
),
[
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_1.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_2.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_3.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_4.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_5.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_6.stl"),
],
load_trimesh_from_stl("src/tests/data/staubli/rx160/base_link.stl"),
Isometry3::from_parts(
Translation3::new(0.4, 0.7, 0.0).into(),
UnitQuaternion::identity(),
),
load_trimesh_from_stl("src/tests/data/flag.stl"),
Isometry3::from_parts(
Translation3::new(0.0, 0.0, 0.5).into(),
UnitQuaternion::identity(),
),
vec![
CollisionBody { mesh: monolith.clone(), pose: Isometry3::translation(1., 0., 0.) },
CollisionBody { mesh: monolith.clone(), pose: Isometry3::translation(-1., 0., 0.) },
CollisionBody { mesh: monolith.clone(), pose: Isometry3::translation(0., 1., 0.) },
CollisionBody { mesh: monolith.clone(), pose: Isometry3::translation(0., -1., 0.) },
],
true,
)
}
More examples
examples/cartesian_stroke.rs (line 23)
20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101
pub fn create_rx160_robot() -> KinematicsWithShape {
use rs_opw_kinematics::read_trimesh::load_trimesh_from_stl;
let monolith = load_trimesh_from_stl("src/tests/data/object.stl");
KinematicsWithShape::with_safety(
Parameters {
a1: 0.15,
a2: 0.0,
b: 0.0,
c1: 0.55,
c2: 0.825,
c3: 0.625,
c4: 0.11,
..Parameters::new()
},
// Constraints are used also to sample constraint-compliant random positions
// as needed by this path planner.
Constraints::from_degrees(
[
-225.0..=225.0,
-225.0..=225.0,
-225.0..=225.0,
-225.0..=225.0,
-225.0..=225.0,
-225.0..=225.0,
],
BY_PREV,
),
[
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_1.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_2.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_3.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_4.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_5.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_6.stl"),
],
load_trimesh_from_stl("src/tests/data/staubli/rx160/base_link.stl"),
Isometry3::from_parts(
Translation3::new(0.4, 0.7, 0.0).into(),
UnitQuaternion::identity(),
),
load_trimesh_from_stl("src/tests/data/flag.stl"),
Isometry3::from_parts(
Translation3::new(0.0, 0.0, 0.5).into(),
UnitQuaternion::identity(),
),
vec![
CollisionBody {
mesh: monolith.clone(),
pose: Isometry3::translation(1., 0., 0.),
},
CollisionBody {
mesh: monolith.clone(),
pose: Isometry3::translation(-1., 0., 0.),
},
CollisionBody {
mesh: monolith.clone(),
pose: Isometry3::translation(0., 1., 0.),
},
CollisionBody {
mesh: monolith.clone(),
pose: Isometry3::translation(0., -1., 0.),
},
],
SafetyDistances {
to_environment: 0.05, // Robot should not come closer than 5 cm to pillars
to_robot_default: 0.05, // No closer than 5 cm to itself.
special_distances: SafetyDistances::distances(&[
// Due construction of this robot, these joints are very close, so
// special rules are needed for them.
((J2, J_BASE), NEVER_COLLIDES), // base and J2 cannot collide
((J3, J_BASE), NEVER_COLLIDES), // base and J3 cannot collide
((J2, J4), NEVER_COLLIDES),
((J3, J4), NEVER_COLLIDES),
((J4, J_TOOL), 0.02_f32), // reduce distance requirement to 2 cm.
((J4, J6), 0.02_f32), // reduce distance requirement to 2 cm.
]),
mode: CheckMode::FirstCollisionOnly, // First pose only (true, enough for path planning)
},
)
}
examples/complete_visible_robot.rs (line 34)
30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124
pub fn create_rx160_robot() -> KinematicsWithShape {
use rs_opw_kinematics::read_trimesh::{load_trimesh_from_stl, load_trimesh_from_ply };
// Environment object to collide with.
let monolith = load_trimesh_from_stl("src/tests/data/object.stl");
KinematicsWithShape::with_safety(
// OPW parameters for Staubli RX 160
Parameters {
a1: 0.15,
a2: 0.0,
b: 0.0,
c1: 0.55,
c2: 0.825,
c3: 0.625,
c4: 0.11,
..Parameters::new()
},
// Define constraints directly in degrees, converting internally to radians.
Constraints::from_degrees(
[
-225.0..=225.0,
-225.0..=225.0,
-225.0..=225.0,
-225.0..=225.0,
-225.0..=225.0,
-360.0..=360.0,
],
BY_PREV, // Prioritize previous joint position
),
// Joint meshes
[
// If your meshes, if offset in .stl file, use Trimesh::transform_vertices,
// you may also need Trimesh::scale in some extreme cases.
// If your joints or tool consist of multiple meshes, combine these
// with Trimesh::append
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_1.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_2.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_3.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_4.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_5.stl"),
load_trimesh_from_stl("src/tests/data/staubli/rx160/link_6.stl"),
],
// Base link mesh
load_trimesh_from_stl("src/tests/data/staubli/rx160/base_link.stl"),
// Base transform, this is where the robot is standing
Isometry3::from_parts(
Translation3::new(0.4, 0.7, 0.0).into(),
UnitQuaternion::identity(),
),
// Tool mesh. Load it from .ply file for feature demonstration
load_trimesh_from_ply("src/tests/data/flag.ply"),
// Tool transform, tip (not base) of the tool. The point past this
// transform is known as tool center point (TCP).
Isometry3::from_parts(
Translation3::new(0.0, 0.0, 0.5).into(),
UnitQuaternion::identity(),
),
// Objects around the robot, with global transforms for them.
vec![
CollisionBody {
mesh: monolith.clone(),
pose: Isometry3::translation(1., 0., 0.),
},
CollisionBody {
mesh: monolith.clone(),
pose: Isometry3::translation(-1., 0., 0.),
},
CollisionBody {
mesh: monolith.clone(),
pose: Isometry3::translation(0., 1., 0.),
},
CollisionBody {
mesh: monolith.clone(),
pose: Isometry3::translation(0., -1., 0.),
},
],
SafetyDistances {
to_environment: 0.05, // Robot should not come closer than 5 cm to pillars
to_robot_default: 0.05, // No closer than 5 cm to itself.
special_distances: SafetyDistances::distances(&[
// Due construction of this robot, these joints are very close, so
// special rules are needed for them.
((J2, J_BASE), NEVER_COLLIDES), // base and J2 cannot collide
((J3, J_BASE), NEVER_COLLIDES), // base and J3 cannot collide
((J2, J4), NEVER_COLLIDES),
((J3, J4), NEVER_COLLIDES),
((J4, J_TOOL), 0.02_f32), // reduce distance requirement to 2 cm.
((J4, J6), 0.02_f32), // reduce distance requirement to 2 cm.
]),
mode: CheckMode::AllCollsions, // we need to report all for visualization
// mode: CheckMode::NoCheck, // this is very fast but no collision check
},
)
}