rs_opw_kinematics/kinematics_with_shape.rs
1//! Defines a structure that combines the kinematic model of a robot with its geometrical shape.
2//! This struct provides both the kinematic functionality for computing joint positions and
3//! the physical structure used for collision detection and other geometric calculations.
4
5use crate::collisions::{BaseBody, CheckMode, CollisionBody, RobotBody, SafetyDistances};
6use crate::constraints::Constraints;
7use crate::kinematic_traits::{Joints, Kinematics, Pose, Singularity, Solutions, J6};
8use crate::kinematics_impl::OPWKinematics;
9use crate::parameters::opw_kinematics::Parameters;
10use crate::tool::{Base, Tool};
11use nalgebra::Isometry3;
12use parry3d::shape::TriMesh;
13use std::sync::Arc;
14
15/// Struct that combines the kinematic model of a robot with its geometrical shape.
16/// This struct provides both the kinematic functionality for computing joint positions and
17/// the physical structure used for collision detection and other geometric calculations.
18pub struct KinematicsWithShape {
19 /// The kinematic model of the robot, typically used to compute forward and inverse kinematics.
20 /// This is an abstract trait (`Kinematics`), allowing for different implementations of kinematic models.
21 pub kinematics: Arc<dyn Kinematics>,
22
23 /// The physical structure of the robot, represented by its joint geometries.
24 /// This `RobotBody` contains information about the geometrical shapes of the joints
25 /// and provides functionality for collision detection.
26 pub body: RobotBody,
27}
28
29impl KinematicsWithShape {
30 /// Constructs a new `KinematicsWithShape` instance for a 6DOF robot.
31 /// This method consumes all parameters, moving them inside the robot.
32 /// This is important for meshes that are bulky.
33 ///
34 /// # Parameters
35 ///
36 /// * `opw_parameters` - OPW parameters defining this robot
37 ///
38 /// * `constraints`: joint constraint limits
39 ///
40 /// * `joint_meshes` - An array of [`TriMesh; 6`] representing the meshes for each joint's body.
41 ///
42 /// * `base_mesh` - The mesh of the robot base.
43 /// * `base_transform` - The transform to apply to the base mesh. This transform brings
44 /// the robot into its intended location inside the robotic cell.
45 ///
46 /// * `tool_mesh` - The mesh of the robot's tool, which will also be checked for collisions.
47 /// * `tool_transform` - The transform to apply to the tool mesh. It defines the location
48 /// of the "action point" of the robot whose location and rotation (pose) is the pose
49 /// for direct and inverse kinematics calls.
50 ///
51 /// * `collision_environment` - A vector of collision objects represented by `CollisionBody`,
52 /// where each object includes a mesh and its transform.
53 ///
54 /// * `first_pose_only` - As collision check may be expensive, check if we need multiple
55 /// checked solutions if inverse kinematics, or the first (best) is enough
56 ///
57 /// # Returns
58 ///
59 /// A `KinematicsWithShape` instance with defined kinematic structure and shapes for collision detection.
60 pub fn new(
61 opw_parameters: Parameters,
62 constraints: Constraints,
63 joint_meshes: [TriMesh; 6],
64 base_mesh: TriMesh,
65 base_transform: Isometry3<f64>,
66 tool_mesh: TriMesh,
67 tool_transform: Isometry3<f64>,
68 collision_environment: Vec<CollisionBody>,
69 first_collision_only: bool,
70 ) -> Self {
71 KinematicsWithShape {
72 kinematics: Arc::new(Self::create_robot_with_base_and_tool(
73 base_transform,
74 tool_transform,
75 opw_parameters,
76 constraints,
77 )),
78 body: RobotBody {
79 joint_meshes,
80 base: Some(BaseBody {
81 mesh: base_mesh,
82 base_pose: base_transform.cast(),
83 }),
84 tool: Some(tool_mesh),
85 collision_environment,
86 safety: SafetyDistances::standard(
87 if first_collision_only {
88 CheckMode::FirstCollisionOnly
89 } else {
90 CheckMode::AllCollsions
91 }),
92 },
93 }
94 }
95
96 /// Constructs a new `KinematicsWithShape` instance for a 6DOF robot.
97 /// This method consumes all parameters, moving them inside the robot.
98 /// This is important for meshes that are bulky.
99 ///
100 /// # Parameters
101 ///
102 /// * `opw_parameters` - OPW parameters defining this robot
103 ///
104 /// * `constraints`: joint constraint limits
105 ///
106 /// * `joint_meshes` - An array of [`TriMesh; 6`] representing the meshes for each joint's body.
107 ///
108 /// * `base_mesh` - The mesh of the robot base.
109 /// * `base_transform` - The transform to apply to the base mesh. This transform brings
110 /// the robot into its intended location inside the robotic cell.
111 ///
112 /// * `tool_mesh` - The mesh of the robot's tool, which will also be checked for collisions.
113 /// * `tool_transform` - The transform to apply to the tool mesh. It defines the location
114 /// of the "action point" of the robot whose location and rotation (pose) is the pose
115 /// for direct and inverse kinematics calls.
116 ///
117 /// * `collision_environment` - A vector of collision objects represented by `CollisionBody`,
118 /// where each object includes a mesh and its transform.
119 ///
120 /// * `safety` - defines the minimal allowed distances between collision objects
121 /// and specifies other details on how collisions are checked. In practice
122 /// robot must stay at some safe distance from collision objects rather than touching them.
123 ///
124 /// # Returns
125 ///
126 /// A `KinematicsWithShape` instance with defined kinematic structure and shapes for collision detection.
127 pub fn with_safety(
128 opw_parameters: Parameters,
129 constraints: Constraints,
130 joint_meshes: [TriMesh; 6],
131 base_mesh: TriMesh,
132 base_transform: Isometry3<f64>,
133 tool_mesh: TriMesh,
134 tool_transform: Isometry3<f64>,
135 collision_environment: Vec<CollisionBody>,
136 safety: SafetyDistances,
137 ) -> Self {
138 KinematicsWithShape {
139 kinematics: Arc::new(Self::create_robot_with_base_and_tool(
140 base_transform,
141 tool_transform,
142 opw_parameters,
143 constraints,
144 )),
145 body: RobotBody {
146 joint_meshes,
147 base: Some(BaseBody {
148 mesh: base_mesh,
149 base_pose: base_transform.cast(),
150 }),
151 tool: Some(tool_mesh),
152 collision_environment,
153 safety: safety,
154 },
155 }
156 }
157
158 fn create_robot_with_base_and_tool(
159 base_transform: Isometry3<f64>,
160 tool_transform: Isometry3<f64>,
161 opw_parameters: Parameters,
162 constraints: Constraints,
163 ) -> Tool {
164 let plain_robot = OPWKinematics::new_with_constraints(opw_parameters, constraints);
165
166 let robot_with_base = Base {
167 robot: Arc::new(plain_robot),
168 base: base_transform.clone(),
169 };
170
171 let robot_with_base_and_tool = Tool {
172 robot: Arc::new(robot_with_base),
173 tool: tool_transform.clone(),
174 };
175
176 robot_with_base_and_tool
177 }
178}
179
180/// Struct representing a robot with positioned joints.
181/// It contains a vector of references to `PositionedJoint`, where each joint has its precomputed global transform.
182///
183/// This struct is useful when performing operations that require knowing the precomputed positions and orientations
184/// of all the joints in the robot, such as forward kinematics, inverse kinematics, and collision detection.
185pub struct PositionedRobot<'a> {
186 /// A vector of references to `PositionedJoint`, representing the joints and their precomputed transforms.
187 pub joints: Vec<PositionedJoint<'a>>,
188 pub tool: Option<PositionedJoint<'a>>,
189 pub environment: Vec<&'a CollisionBody>,
190}
191
192/// Struct representing a positioned joint, which consists of a reference to a `JointBody`
193/// and its precomputed combined transform. This is the global transform of the joint combined with
194/// the local transforms of the collision shapes within the joint.
195///
196/// This struct simplifies access to the final world-space transform of the joint's shapes.
197pub struct PositionedJoint<'a> {
198 /// A reference to the associated `JointBody` that defines the shapes and collision behavior of the joint.
199 pub joint_body: &'a TriMesh,
200
201 /// The combined transformation matrix (Isometry3), representing the precomputed global position
202 /// and orientation of the joint in the world space.
203 pub transform: Isometry3<f32>,
204}
205
206impl KinematicsWithShape {
207 /// Method to compute and return a `PositionedRobot` from the current `RobotBody` and a set of joint positions.
208 ///
209 /// This method uses the forward kinematics to compute the global transforms of each joint
210 /// and then creates the corresponding `PositionedJoint` instances, which are collected into a `PositionedRobot`.
211 ///
212 /// # Arguments
213 ///
214 /// * `joint_positions` - A reference to the joint values (angles/positions) to compute the forward kinematics.
215 ///
216 /// # Returns
217 ///
218 /// * A new instance of `PositionedRobot` containing the positioned joints with precomputed transforms.
219 pub fn positioned_robot(&self, joint_positions: &Joints) -> PositionedRobot<'_> {
220 // Compute the global transforms for each joint using forward kinematics
221 let global_transforms: [Isometry3<f32>; 6] = self
222 .kinematics
223 .forward_with_joint_poses(joint_positions)
224 .map(|pose| pose.cast::<f32>());
225
226 // Create a vector of PositionedJoints without mut
227 let positioned_joints: Vec<PositionedJoint> = self
228 .body
229 .joint_meshes
230 .iter()
231 .enumerate()
232 .map(|(i, joint_body)| PositionedJoint {
233 joint_body,
234 transform: global_transforms[i],
235 })
236 .collect();
237
238 // Return the PositionedRobot with all the positioned joints
239 let positioned_tool = if let Some(tool) = self.body.tool.as_ref() {
240 Some(PositionedJoint {
241 joint_body: tool,
242 transform: global_transforms[J6], // TCP pose
243 })
244 } else {
245 None
246 };
247
248 // Convert to vector of references
249 let referenced_environment = self.body.collision_environment.iter().collect();
250
251 PositionedRobot {
252 joints: positioned_joints,
253 tool: positioned_tool,
254 environment: referenced_environment,
255 }
256 }
257}
258
259impl KinematicsWithShape {
260 /// Remove solutions that are reported as result the robot colliding with self or
261 /// environment. Only retain non-colliding solutions. If safety distances are specified
262 /// with the distance, also discards solutions where robot comes too close to
263 /// collision rather than collides.
264 pub(crate) fn remove_collisions(&self, solutions: Solutions) -> Solutions {
265 let mut filtered_solutions = Vec::with_capacity(solutions.len());
266 for solution in solutions {
267 if !self.body.collides(&solution, self.kinematics.as_ref()) {
268 filtered_solutions.push(solution);
269 }
270 }
271 filtered_solutions
272 }
273
274 /// Check for collisions for the given joint position. Both self-collisions and collisions
275 /// with environment are checked. This method simply returns true (if collides) or false (if not)
276 // If safety distances are specified, also returns true for solutions where robot comes
277 // too close to collision rather than collides.
278 pub fn collides(&self, joints: &Joints) -> bool {
279 self.body.collides(joints, self.kinematics.as_ref())
280 }
281
282 /// Return non colliding offsets, tweaking each joint plus minus either side, either into
283 /// 'to' or into 'from'. This is required for planning algorithms like A*. We can do
284 /// less collision checks as we only need to check the joint branch of the robot we moved.
285 // If safety distances are specified, also discards solutions where robot comes
286 // too close to collision rather than collides.
287 pub fn non_colliding_offsets(&self, joints: &Joints, from: &Joints, to: &Joints) -> Solutions {
288 self.body
289 .non_colliding_offsets(joints, from, to, self.kinematics.as_ref())
290 }
291
292 /// Provide details about he collision, who with whom collides or comes too near.
293 /// Depending on if the RobotBody has been configured for complete check,
294 /// either all collisions or only the first found colliding pair
295 /// is returned.
296 pub fn collision_details(&self, joints: &Joints) -> Vec<(usize, usize)> {
297 self.body
298 .collision_details(joints, self.kinematics.as_ref())
299 }
300
301 /// Allows overriding collision check with the custom instance of safety distance.
302 /// This is needed when the safety configuration is adaptive/dynamic rather than fixed.
303 pub fn near(&self, joints: &Joints, safety: &SafetyDistances) -> Vec<(usize, usize)> {
304 self.body.near(joints, self.kinematics.as_ref(), safety)
305 }
306}
307
308impl Kinematics for KinematicsWithShape {
309 /// Delegates call to underlying Kinematics, but will filter away colliding poses
310 fn inverse(&self, pose: &Pose) -> Solutions {
311 let solutions = self.kinematics.inverse(pose);
312 self.remove_collisions(solutions)
313 }
314
315 /// Delegates call to underlying Kinematics, but will filter away colliding poses
316 fn inverse_continuing(&self, pose: &Pose, previous: &Joints) -> Solutions {
317 let solutions = self.kinematics.inverse_continuing(pose, previous);
318 self.remove_collisions(solutions)
319 }
320
321 fn forward(&self, qs: &Joints) -> Pose {
322 self.kinematics.forward(qs)
323 }
324
325 /// Delegates call to underlying Kinematics, but will filter away colliding poses
326 fn inverse_5dof(&self, pose: &Pose, j6: f64) -> Solutions {
327 let solutions = self.kinematics.inverse_5dof(pose, j6);
328 self.remove_collisions(solutions)
329 }
330
331 /// Delegates call to underlying Kinematics, but will filter away colliding poses
332 fn inverse_continuing_5dof(&self, pose: &Pose, prev: &Joints) -> Solutions {
333 let solutions = self.kinematics.inverse_continuing_5dof(pose, prev);
334 self.remove_collisions(solutions)
335 }
336
337 fn constraints(&self) -> &Option<Constraints> {
338 self.kinematics.constraints()
339 }
340
341 fn kinematic_singularity(&self, qs: &Joints) -> Option<Singularity> {
342 self.kinematics.kinematic_singularity(qs)
343 }
344
345 fn forward_with_joint_poses(&self, joints: &Joints) -> [Pose; 6] {
346 self.kinematics.forward_with_joint_poses(joints)
347 }
348}