From 848bf8f6ef51a503ff9e15de1b32934eca05e585 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 20:40:58 +0900 Subject: [PATCH] return or value for :go-pos-unsafe --- pr2eus/robot-interface.l | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/pr2eus/robot-interface.l b/pr2eus/robot-interface.l index 0f3b1f10..df36c7e8 100644 --- a/pr2eus/robot-interface.l +++ b/pr2eus/robot-interface.l @@ -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)