|
| 1 | +#!/usr/bin/env roseus |
| 2 | +(require :unittest "lib/llib/unittest.l") |
| 3 | +(require "package://jsk_2016_01_baxter_apc/euslisp/jsk_2016_01_baxter_apc/baxter.l") |
| 4 | +(load "package://jsk_2015_05_baxter_apc/euslisp/test/data/bin-cubes.l") |
| 5 | + |
| 6 | +(init-unit-test) |
| 7 | + |
| 8 | +(defun setup () |
| 9 | + (unless (boundp '*baxter*) |
| 10 | + (setq *baxter* (instance jsk_2016_01_baxter_apc::baxter-robot :init))) |
| 11 | + (objects (list *baxter*)) |
| 12 | + (send *baxter* :angle-vector #f(0.0 97.4707 -2.39502 -94.5483 134.67 91.4062 8.70117 0.0 -5.40301 55.9257 117.063 72.4793 -62.7243 -7.73117 -87.322 90.0)) |
| 13 | + ) |
| 14 | + |
| 15 | +(defun check-result (av1 av2) |
| 16 | + (let () |
| 17 | + (when (and av1 av2) |
| 18 | + (format t "av1 = ~A~%" av1) |
| 19 | + (format t "av2 = ~A~%" av2) |
| 20 | + (format t "diff = ~A (~A)~%" (v- av2 av1) (norm (v- av2 av1))) |
| 21 | + (do ((i 0 (incf i 0.1))) |
| 22 | + ((>= i 1)) |
| 23 | + (send *baxter* :angle-vector (midpoint i av1 av2)) |
| 24 | + (send *irtviewer* :draw-objects) |
| 25 | + (print i)) |
| 26 | + ))) |
| 27 | + |
| 28 | +(deftest issue-1474 () ;; https://github.com/start-jsk/jsk_apc/issues/1470#issuecomment-220518802 |
| 29 | + (let (av1 av2) |
| 30 | + (setup) |
| 31 | + (setq av1 (send *baxter* :angle-vector)) |
| 32 | + (send *baxter* :rarm :move-end-pos #f(0 0 -50) :local) |
| 33 | + (setq av2 (send *baxter* :angle-vector)) ;; #f(0.0 97.4707 -2.39502 -94.5483 134.67 91.4062 8.70117 0.0 -8.22871 40.7953 92.2281 64.6958 -80.3615 -21.3969 -46.1696 90.0) |
| 34 | + (check-result av1 av2) |
| 35 | + (assert (and av1 av2)) |
| 36 | + (assert (< (norm (v- av1 av2)) 10)) |
| 37 | + )) |
| 38 | + |
| 39 | +;; check why normal ik failed |
| 40 | +(deftest check-normal-ik-1 () ;; this uses exactry the same parameter with baxter-robot :inverse-kinematics in baxtereus/baxter-util.l |
| 41 | + (let (av1 av2) |
| 42 | + (setup) |
| 43 | + (setq av1 (send *baxter* :angle-vector)) |
| 44 | + (send *irtviewer* :draw-objects) |
| 45 | + (setq av2 (send-message *baxter* robot-model :inverse-kinematics |
| 46 | + (send (send *baxter* :rarm :end-coords :copy-worldcoords) :translate #f(0 0 -50) :local) |
| 47 | + :additional-weight-list (mapcar #'(lambda (jn) (list (send *baxter* jn :child-link) 0)) |
| 48 | + '(:right_gripper_vacuum_pad_joint)) |
| 49 | + :move-target (send *baxter* :rarm :end-coords) |
| 50 | + :link-list (send *baxter* :link-list (send *baxter* :rarm :end-coords :parent) (send *baxter* :rarm :root-link)) |
| 51 | + :avoid-collision-distance 5 |
| 52 | + :debug-view nil ;; set true for debugging |
| 53 | + )) |
| 54 | + (check-result av1 av2) |
| 55 | + ;; (assert (and av1 av2)) ;; this is expected to fail without new irteus |
| 56 | + )) |
| 57 | + |
| 58 | +(deftest check-normal-ik-2 () ;; this may fix the problem |
| 59 | + (let (av1 av2) |
| 60 | + (setup) |
| 61 | + (setq av1 (send *baxter* :angle-vector)) |
| 62 | + (send *irtviewer* :draw-objects) |
| 63 | + (setq av2 (send-message *baxter* robot-model :inverse-kinematics |
| 64 | + (send (send *baxter* :rarm :end-coords :copy-worldcoords) :translate #f(0 0 -50) :local) |
| 65 | + :move-target (send *baxter* :rarm :end-coords) |
| 66 | + ;;:link-list (send *baxter* :link-list (send *baxter* :rarm :end-coords :parent) (send *baxter* :rarm :root-link)) |
| 67 | + :link-list (send *baxter* :link-list (send *baxter* :right_gripper_vacuum_pad_joint :parent-link) (send *baxter* :rarm :root-link)) |
| 68 | + :avoid-collision-distance 5 |
| 69 | + :debug-view nil ;; set true for debugging |
| 70 | + )) |
| 71 | + (check-result av1 av2) |
| 72 | + (assert (and av1 av2)) |
| 73 | + )) |
| 74 | + |
| 75 | +(run-all-tests) |
| 76 | +(exit) |
0 commit comments