1use std::fmt;
18
19use na::{DVector, Isometry3, RealField, Vector3, Vector6};
20use nalgebra as na;
21#[cfg(feature = "serde")]
22use serde::{Deserialize, Serialize};
23use simba::scalar::SubsetOf;
24
25use super::chain::*;
26use super::errors::*;
27use super::funcs::*;
28
29fn calc_pose_diff<T>(a: &Isometry3<T>, b: &Isometry3<T>) -> Vector6<T>
31where
32 T: RealField,
33{
34 let p_diff = a.translation.vector.clone() - b.translation.vector.clone();
35 let w_diff = b.rotation.rotation_to(&a.rotation).scaled_axis();
36 Vector6::new(
37 p_diff[0].clone(),
38 p_diff[1].clone(),
39 p_diff[2].clone(),
40 w_diff[0].clone(),
41 w_diff[1].clone(),
42 w_diff[2].clone(),
43 )
44}
45
46fn calc_pose_diff_with_constraints<T>(
47 a: &Isometry3<T>,
48 b: &Isometry3<T>,
49 operational_space: [bool; 6],
50) -> DVector<T>
51where
52 T: RealField,
53{
54 let full_diff = calc_pose_diff(a, b);
55 let use_dof = operational_space.iter().filter(|x| **x).count();
56 let mut diff = DVector::from_element(use_dof, na::zero());
57 let mut index = 0;
58 for (i, use_i) in operational_space.iter().enumerate() {
59 if *use_i {
60 diff[index] = full_diff[i].clone();
61 index += 1;
62 }
63 }
64 diff
65}
66
67#[derive(Clone, Debug)]
69#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
70pub struct Constraints {
71 #[cfg_attr(feature = "serde", serde(default = "default_true"))]
74 pub position_x: bool,
75 #[cfg_attr(feature = "serde", serde(default = "default_true"))]
76 pub position_y: bool,
77 #[cfg_attr(feature = "serde", serde(default = "default_true"))]
78 pub position_z: bool,
79 #[cfg_attr(feature = "serde", serde(default = "default_true"))]
80 pub rotation_x: bool,
81 #[cfg_attr(feature = "serde", serde(default = "default_true"))]
82 pub rotation_y: bool,
83 #[cfg_attr(feature = "serde", serde(default = "default_true"))]
84 pub rotation_z: bool,
85 #[cfg_attr(feature = "serde", serde(default))]
86 pub ignored_joint_names: Vec<String>,
87}
88
89fn default_true() -> bool {
90 true
91}
92
93impl Default for Constraints {
94 fn default() -> Self {
107 Self {
108 position_x: default_true(),
109 position_y: default_true(),
110 position_z: default_true(),
111 rotation_x: default_true(),
112 rotation_y: default_true(),
113 rotation_z: default_true(),
114 ignored_joint_names: Default::default(),
115 }
116 }
117}
118
119fn define_operational_space(constraints: &Constraints) -> [bool; 6] {
120 let mut arr = [true; 6];
121 arr[0] = constraints.position_x;
122 arr[1] = constraints.position_y;
123 arr[2] = constraints.position_z;
124 arr[3] = constraints.rotation_x;
125 arr[4] = constraints.rotation_y;
126 arr[5] = constraints.rotation_z;
127 arr
128}
129
130pub trait InverseKinematicsSolver<T>
132where
133 T: RealField,
134{
135 fn solve(&self, arm: &SerialChain<T>, target_pose: &Isometry3<T>) -> Result<(), Error> {
137 self.solve_with_constraints(arm, target_pose, &Constraints::default())
138 }
139 fn solve_with_constraints(
141 &self,
142 arm: &SerialChain<T>,
143 target_pose: &Isometry3<T>,
144 constraints: &Constraints,
145 ) -> Result<(), Error>;
146}
147
148pub struct JacobianIkSolver<T: RealField> {
150 pub allowable_target_distance: T,
152 pub allowable_target_angle: T,
154 pub jacobian_multiplier: T,
156 pub num_max_try: usize,
158 #[allow(clippy::type_complexity)]
160 nullspace_function: Option<Box<dyn Fn(&[T]) -> Vec<T> + Send + Sync>>,
161}
162
163impl<T> JacobianIkSolver<T>
164where
165 T: RealField + SubsetOf<f64>,
166{
167 pub fn new(
177 allowable_target_distance: T,
178 allowable_target_angle: T,
179 jacobian_multiplier: T,
180 num_max_try: usize,
181 ) -> JacobianIkSolver<T> {
182 JacobianIkSolver {
183 allowable_target_distance,
184 allowable_target_angle,
185 jacobian_multiplier,
186 num_max_try,
187 nullspace_function: None,
188 }
189 }
190 #[allow(clippy::type_complexity)]
204 pub fn set_nullspace_function(&mut self, func: Box<dyn Fn(&[T]) -> Vec<T> + Send + Sync>) {
205 self.nullspace_function = Some(func);
206 }
207
208 pub fn clear_nullspace_function(&mut self) {
210 self.nullspace_function = None;
211 }
212
213 fn add_positions_with_multiplier(&self, input: &[T], add_values: &[T]) -> Vec<T> {
214 input
215 .iter()
216 .zip(add_values.iter())
217 .map(|(ang, add)| ang.clone() + self.jacobian_multiplier.clone() * add.clone())
218 .collect()
219 }
220
221 fn solve_one_loop_with_constraints(
222 &self,
223 arm: &SerialChain<T>,
224 target_pose: &Isometry3<T>,
225 operational_space: &[bool; 6],
226 ignored_joint_indices: &[usize],
227 ) -> Result<DVector<T>, Error> {
228 let required_dof = operational_space.iter().filter(|x| **x).count();
229 let orig_positions = arm.joint_positions();
230 let available_dof = arm.dof() - ignored_joint_indices.len();
231
232 let t_n = arm.end_transform();
233 let err = calc_pose_diff_with_constraints(target_pose, &t_n, *operational_space);
234 let mut jacobi = jacobian(arm);
235 let mut num_removed_rows = 0;
236 for (i, use_i) in operational_space.iter().enumerate() {
237 if !use_i {
238 jacobi = jacobi.remove_row(i - num_removed_rows);
239 num_removed_rows += 1;
240 }
241 }
242
243 for (i, joint_index) in ignored_joint_indices.iter().enumerate() {
244 jacobi = jacobi.remove_column(*joint_index - i);
245 }
246
247 let positions_vec = if available_dof > required_dof {
248 const EPS: f64 = 0.0001;
249 match self.nullspace_function {
251 Some(ref f) => {
252 let jacobi_inv = jacobi.clone().pseudo_inverse(na::convert(EPS)).unwrap();
253
254 let mut subtask = na::DVector::from_vec(f(&orig_positions));
255 for (i, joint_index) in ignored_joint_indices.iter().enumerate() {
256 subtask = subtask.remove_row(*joint_index - i);
257 }
258 let mut d_q = jacobi_inv.clone() * err
259 + (na::DMatrix::identity(available_dof, available_dof)
260 - jacobi_inv * jacobi)
261 * subtask;
262 for joint_index in ignored_joint_indices {
263 d_q = d_q.insert_row(*joint_index, T::zero());
264 }
265 self.add_positions_with_multiplier(&orig_positions, d_q.as_slice())
266 }
267 None => {
268 let mut d_q = jacobi
269 .svd(true, true)
270 .solve(&err, na::convert(EPS))
271 .unwrap();
272 for joint_index in ignored_joint_indices {
273 d_q = d_q.insert_row(*joint_index, T::zero());
274 }
275 self.add_positions_with_multiplier(&orig_positions, d_q.as_slice())
276 }
277 }
278 } else {
279 self.add_positions_with_multiplier(
281 &orig_positions,
282 jacobi
283 .lu()
284 .solve(&err)
285 .ok_or(Error::InverseMatrixError)?
286 .as_slice(),
287 )
288 };
289 arm.set_joint_positions_clamped(&positions_vec);
290 Ok(calc_pose_diff_with_constraints(
291 target_pose,
292 &arm.end_transform(),
293 *operational_space,
294 ))
295 }
296
297 fn solve_with_constraints_internal(
298 &self,
299 arm: &SerialChain<T>,
300 target_pose: &Isometry3<T>,
301 constraints: &Constraints,
302 ) -> Result<(), Error> {
303 let operational_space = define_operational_space(constraints);
304 let required_dof = operational_space.iter().filter(|x| **x).count();
305 let orig_positions = arm.joint_positions();
306 let available_dof = arm.dof() - constraints.ignored_joint_names.len();
307 if available_dof < required_dof {
308 return Err(Error::PreconditionError {
309 dof: available_dof,
310 necessary_dof: required_dof,
311 });
312 }
313 let mut ignored_joint_indices = Vec::new();
314 for joint_name in &constraints.ignored_joint_names {
315 match arm.iter_joints().position(|x| x.name == *joint_name) {
317 Some(index) => {
318 ignored_joint_indices.push(index);
319 }
320 None => {
321 return Err(Error::InvalidJointNameError {
322 joint_name: joint_name.to_string(),
323 });
324 }
325 }
326 }
327 ignored_joint_indices.sort_unstable();
328 let mut last_target_distance = None;
329 for _ in 0..self.num_max_try {
330 let target_diff = self.solve_one_loop_with_constraints(
331 arm,
332 target_pose,
333 &operational_space,
334 &ignored_joint_indices,
335 )?;
336 let (len_diff, rot_diff) = target_diff_to_len_rot_diff(&target_diff, operational_space);
337 if len_diff.norm() < self.allowable_target_distance
338 && rot_diff.norm() < self.allowable_target_angle
339 {
340 let non_checked_positions = arm.joint_positions();
341 arm.set_joint_positions_clamped(&non_checked_positions);
342 return Ok(());
343 }
344 last_target_distance = Some((len_diff, rot_diff));
345 }
346 arm.set_joint_positions(&orig_positions)?;
347 Err(Error::NotConvergedError {
348 num_tried: self.num_max_try,
349 position_diff: na::try_convert(last_target_distance.as_ref().unwrap().0.clone())
350 .unwrap_or_default(),
351 rotation_diff: na::try_convert(last_target_distance.as_ref().unwrap().1.clone())
352 .unwrap_or_default(),
353 })
354 }
355}
356
357impl<T: RealField + fmt::Debug> fmt::Debug for JacobianIkSolver<T> {
358 fn fmt(&self, f: &mut fmt::Formatter<'_>) -> fmt::Result {
359 f.debug_struct("JacobianIkSolver")
360 .field("allowable_target_distance", &self.allowable_target_distance)
361 .field("allowable_target_angle", &self.allowable_target_angle)
362 .field("jacobian_multiplier", &self.jacobian_multiplier)
363 .field("num_max_try", &self.num_max_try)
364 .field("has_nullspace_function", &self.nullspace_function.is_some())
365 .finish()
366 }
367}
368
369fn target_diff_to_len_rot_diff<T>(
370 target_diff: &DVector<T>,
371 operational_space: [bool; 6],
372) -> (Vector3<T>, Vector3<T>)
373where
374 T: RealField,
375{
376 let mut len_diff = Vector3::zeros();
377 let mut index = 0;
378 for i in 0..3 {
379 if operational_space[i] {
380 len_diff[i] = target_diff[index].clone();
381 index += 1;
382 }
383 }
384 let mut rot_diff = Vector3::zeros();
385 for i in 0..3 {
386 if operational_space[i + 3] {
387 rot_diff[i] = target_diff[index].clone();
388 index += 1;
389 }
390 }
391 (len_diff, rot_diff)
392}
393
394impl<T> InverseKinematicsSolver<T> for JacobianIkSolver<T>
395where
396 T: RealField + SubsetOf<f64>,
397{
398 fn solve(&self, arm: &SerialChain<T>, target_pose: &Isometry3<T>) -> Result<(), Error> {
432 self.solve_with_constraints(arm, target_pose, &Constraints::default())
433 }
434
435 fn solve_with_constraints(
466 &self,
467 arm: &SerialChain<T>,
468 target_pose: &Isometry3<T>,
469 constraints: &Constraints,
470 ) -> Result<(), Error> {
471 let orig_positions = arm.joint_positions();
472 let re = self.solve_with_constraints_internal(arm, target_pose, constraints);
473 if re.is_err() {
474 arm.set_joint_positions(&orig_positions)?;
475 };
476 re
477 }
478}
479
480impl<T> Default for JacobianIkSolver<T>
481where
482 T: RealField + SubsetOf<f64>,
483{
484 fn default() -> Self {
485 Self::new(na::convert(0.001), na::convert(0.005), na::convert(0.5), 10)
486 }
487}
488
489pub fn create_reference_positions_nullspace_function<T: RealField>(
497 reference_positions: Vec<T>,
498 weight_vector: Vec<T>,
499) -> impl Fn(&[T]) -> Vec<T> {
500 let dof = reference_positions.len();
501 assert_eq!(dof, weight_vector.len());
502
503 move |positions| {
504 let mut derivative_vec = vec![na::convert(0.0); dof];
505 for i in 0..dof {
506 derivative_vec[i] =
507 weight_vector[i].clone() * (positions[i].clone() - reference_positions[i].clone());
508 }
509 derivative_vec
510 }
511}
512
513#[cfg(test)]
514mod tests {
515 use super::*;
516 #[cfg(target_family = "wasm")]
517 use wasm_bindgen_test::wasm_bindgen_test as test;
518
519 #[test]
520 fn test_nullspace_func() {
521 let f = create_reference_positions_nullspace_function(vec![0.0, 1.0], vec![0.5, 0.1]);
522 let pos1 = vec![0.5, 0.5];
523 let values = f(&pos1);
524 assert_eq!(values.len(), 2);
525 assert!((values[0] - 0.25f64).abs() < f64::EPSILON);
526 assert!((values[1] - (-0.05f64)).abs() < f64::EPSILON);
527 }
528}