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

[fetcheus] :go-pos-unsafe for kinematic simulation #1740

Merged
merged 2 commits into from
Dec 13, 2022
Merged
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
6 changes: 6 additions & 0 deletions jsk_fetch_robot/fetcheus/fetch-interface.l
Original file line number Diff line number Diff line change
Expand Up @@ -415,18 +415,24 @@ Example: (send self :gripper :position) => 0.00"
t)
(:go-pos-unsafe
(x y d &rest args) ;; [m] [m] [degree]
(if (send self :simulation-modep)
(return-from :go-pos-unsafe (send-super* :go-pos-unsafe x y d args)))
(send self :put :go-pos-unsafe-no-wait-goal (float-vector x y d))
(send* self :go-pos-unsafe-wait args)
t)
(:go-pos-unsafe-no-wait
(x y &optional (d 0)) ;; [m] [m] [degree]
(if (send self :simulation-modep)
(return-from :go-pos-unsafe-no-wait (send-super :go-pos-unsafe-no-wait x y d)))
(ros::ros-warn ":go-pos-unsafe-no-wait is not supported for this robot.")
(send self :put :go-pos-unsafe-no-wait-goal (float-vector x y d))
t)
(:go-pos-unsafe-wait
(&key (translation-threshold 0.05) (rotation-threshold (deg2rad 5))
(translation-gain 1.0) (rotation-gain 1.0)
(min-translation-abs-vel 0.3) (min-rotation-abs-vel 0.8))
(if (send self :simulation-modep)
(return-from :go-pos-unsafe-wait (send-super :go-pos-unsafe-wait)))
(unless (send self :get :go-pos-unsafe-no-wait-goal)
(ros::ros-error ":go-pos-unsafe-wait is called without goal")
(return-from :go-pos-unsafe-wait nil))
Expand Down
17 changes: 17 additions & 0 deletions jsk_fetch_robot/fetcheus/test/test-fetcheus.l
Original file line number Diff line number Diff line change
Expand Up @@ -126,6 +126,23 @@
(format nil ":go-velocity returns t with argument ~A" go-vel-arg))
))

;; test for kinematics simulation
(deftest fetch-go-pos
(let (go-pos-arg)
(setq go-pos-arg (list 0.1 0.1 0.5))
(assert (send* *ri* :go-pos go-pos-arg)
(format nil ":go-pos doesn't return t with argument ~A" go-pos-arg))
))

;; test for kinematics simulation
(deftest fetch-go-pos-unsafe
(let (go-pos-arg)
(setq go-pos-arg (list 0.1 0.1 0.5))
;; :go-pos-unsafe returns nil
(assert (null (send* *ri* :go-pos-unsafe go-pos-arg))
(format nil ":go-pos-unsafe doesn't return t with argument ~A" go-pos-arg))
))

(deftest fetch-use-torso
(let ()
(setq *ri* (instance fetch-interface :init))
Expand Down