Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[pr2-interface.l] check :check-continuous-joint-move-over-180 when simulator mode #452

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions pr2eus/pr2-interface.l
Original file line number Diff line number Diff line change
Expand Up @@ -421,8 +421,8 @@ Example: (send self :gripper :rarm :position) => 0.00"
))
(:angle-vector-sequence
(avs &optional (tms (list 3000)) &rest args)
(unless (or (send self :simulation-modep) (cadr (memq :end-coords-interpolation args)))
(let* ((prev-av (send robot :angle-vector (send self :state :reference-vector)))
(unless (cadr (memq :end-coords-interpolation args))
(let* ((prev-av (send robot :angle-vector (if (send self :simulation-modep) (send self :state :potentio-vector) (send self :state :reference-vector))))
Comment on lines -424 to +425
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This did not existing tests

may be

   (unless (or (send self :simulation-modep) (cadr (memq :end-coords-interpolation args)))
     (let* ((prev-av (send robot :angle-vector (if (send self :simulation-modep) (send self :state :potentio-vector) (send self :state :reference-vector))))

??? please pass tests @Naoki-Hiraoka
https://github.com/jsk-ros-pkg/jsk_pr2eus/actions/runs/3317672989/jobs/5480786114

  + catkin_test_results --verbose --all build
  Full test results for 'pr2eus_moveit/test_results/pr2eus_moveit/rosunit-test_pr2eus_moveit_sim.xml'
  -------------------------------------------------
  <testsuite tests="2" failures="1" disabled="0" errors="0" time="0" name="AllTests">
    <testcase name="all-test" status="run" time="0" classname="all-test">
     <failure message="number expected" type="AssertionError">
  Test:(/ (elt tms l) div)
  Trace:32
  Message:"number expected"
     </failure>
    </testcase>
    <testcase name="test-angle-vector-motion-plan" status="run" time="0" classname="test-angle-vector-motion-plan">
    </testcase>
  </testsuite>

(len-av (length prev-av))
(max-av (fill (instantiate float-vector len-av) 180))
(min-av (fill (instantiate float-vector len-av) -180))
Expand Down
42 changes: 42 additions & 0 deletions pr2eus/test/pr2-ri-test-simple-angle-vector.l
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,48 @@
)
))

(deftest test-angle-vector-unlimited-robot-interface
(let (msg)
(dolist (inc (list 10 -10))
(do ((i 0.0 (incf i inc)))
((if (> inc 0) (<= 1000 i) (>= -1000 i)))
(send *pr2* :reset-manip-pose)
(send *ri* :robot :reset-manip-pose)
(send *ri* :robot-interface-simulation-callback) ;; publish robot-state
(let ((initial-angle (elt (send *ri* :state :potentio-vector) 5)))
(send *pr2* :larm :elbow-r :joint-angle i)
(send-message *ri* robot-interface :angle-vector (send *pr2* :angle-vector) 500)
(send *ri* :wait-interpolation)
(setq msg
(format nil "initial ~A, *ri* ~A, *pr2* ~A ~A~%"
initial-angle
(elt (send *ri* :state :potentio-vector) 5)
(elt (send *pr2* :angle-vector) 5)
(eps<= (abs (- (elt (send *ri* :state :potentio-vector) 5) initial-angle)) 180.0 1.0)))
(warning-message 2 msg)
(assert (eps<= (abs (- (elt (send *ri* :state :potentio-vector) 5) initial-angle)) 180.0 1.0) msg))))))

(deftest test-angle-vector-unlimited-pr2-interface
(let (msg)
(dolist (inc (list 10 -10))
(do ((i 0.0 (incf i inc)))
((if (> inc 0) (<= 1000 i) (>= -1000 i)))
(send *pr2* :reset-manip-pose)
(send *ri* :robot :reset-manip-pose)
(send *ri* :robot-interface-simulation-callback) ;; publish robot-state
(let ((initial-angle (elt (send *ri* :state :potentio-vector) 5)))
(send *pr2* :larm :elbow-r :joint-angle i)
(send-message *ri* pr2-interface :angle-vector (send *pr2* :angle-vector) 500)
(send *ri* :wait-interpolation)
(setq msg
(format nil "initial ~A, *ri* ~A, *pr2* ~A ~A~%"
initial-angle
(elt (send *ri* :state :potentio-vector) 5)
(elt (send *pr2* :angle-vector) 5)
(eps= (elt (send *ri* :state :potentio-vector) 5) (elt (send *pr2* :angle-vector) 5) 1.0)))
(warning-message 2 msg)
(assert (eps= (elt (send *ri* :state :potentio-vector) 5) (elt (send *pr2* :angle-vector) 5) 1.0) msg))))))


(run-all-tests)
(exit)