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

[pr2eus] go-pos-unsafe return t when the motion is correctly executed. #491

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
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: 4 additions & 2 deletions pr2eus/robot-interface.l
Original file line number Diff line number Diff line change
Expand Up @@ -1697,8 +1697,8 @@ Return value is a list of interpolatingp for all controllers, so (null (some #'i
(if wait (send move-base-trajectory-action :wait-for-result)))
))
(:go-pos-unsafe (&rest args)
(send* self :go-pos-unsafe-no-wait args)
(send self :go-pos-unsafe-wait))
(or (send* self :go-pos-unsafe-no-wait args)
(send self :go-pos-unsafe-wait)))
(:go-pos-unsafe-no-wait
(x y &optional (d 0)) ;; [m] [m] [degree]
(ros::ros-info "go-pos-unsafe (x y d) = (~A ~A ~A)" x y d)
Expand Down Expand Up @@ -1760,6 +1760,8 @@ Return value is a list of interpolatingp for all controllers, so (null (some #'i
x y (deg2rad d) msec
:stop t))
(send move-base-trajectory-action :send-goal go-pos-unsafe-goal-msg)
;; check if the action moves properly in :go-pos-unsafe-wait
(return-from :go-pos-unsafe-no-wait nil)
))
(:go-pos-unsafe-wait ()
(let (x y d msec step goal (maxvel 0.295) (maxrad 0.495) (counter 0))
Expand Down