diff --git a/jsk_baxter_robot/jsk_baxter_startup/baxter.launch b/jsk_baxter_robot/jsk_baxter_startup/baxter.launch
index a6a43e980a..4bc4bde713 100644
--- a/jsk_baxter_robot/jsk_baxter_startup/baxter.launch
+++ b/jsk_baxter_robot/jsk_baxter_startup/baxter.launch
@@ -7,14 +7,14 @@
-
-
+
+
diff --git a/jsk_fetch_robot/fetcheus/fetch-interface.l b/jsk_fetch_robot/fetcheus/fetch-interface.l
index 9c8a9131b4..d2010473a7 100644
--- a/jsk_fetch_robot/fetcheus/fetch-interface.l
+++ b/jsk_fetch_robot/fetcheus/fetch-interface.l
@@ -13,8 +13,8 @@
)
(defmethod fetch-interface
- (:init (&rest args)
- (prog1 (send-super* :init :robot fetch-robot :base-frame-id "/base_link" :odom-topic "/odom_combined" :base-controller-action-name nil args)
+ (:init (&key (default-collision-object t) &rest args)
+ (prog1 (send-super* :init :robot fetch-robot :base-frame-id "base_link" :odom-topic "/odom_combined" :base-controller-action-name nil args)
(send self :add-controller :arm-controller)
(send self :add-controller :torso-controller)
(send self :add-controller :head-controller)
@@ -29,10 +29,18 @@
:groupname groupname))
(setq moveit-robot (instance fetch-robot :init))
(send self :set-moveit-environment (instance fetch-moveit-environment :init :robot moveit-robot))
+ (when (and (boundp '*co*) default-collision-object)
+ (send self :delete-keepout-collision-object)
+ (send self :delete-ground-collision-object)
+ (send self :add-keepout-collision-object)
+ (send self :add-ground-collision-object))
))
(:state (&rest args)
":state calls with :wait-until-update by default, since Fetch publishes /joint_states from body and gripper at almost same frequency"
- (send-super* :state (if (member :wait-until-update args) args (append args (list :wait-until-update t)))))
+ (send-super* :state
+ (if (or (eq (car args) :worldcoords)
+ (member :wait-until-update args))
+ args (append args (list :wait-until-update t)))))
(:check-continuous-joint-move-over-180 ;; can be removed if http//github.com/jsk-ros-pkg/jsk_pr2eus/pull/322 merged
(diff-av)
(let ((i 0) add-new-trajectory-point)
@@ -191,7 +199,26 @@ Example: (send self :gripper :position) => 0.00"
(send-super* :speak-en text :topic-name topic-name args))
(:speak-jp (text &rest args &key (topic-name "robotsound_jp") &allow-other-keys)
(send-super* :speak-jp text :topic-name topic-name args))
- )
+ (:add-keepout-collision-object ()
+ (let ((cube (make-cube 200 350 50))
+ (keepout (make-cylinder 300 50)))
+ (send cube :translate #f(-120 0 0))
+ (send keepout :translate #f(0 0 -25))
+ (setq keepout (body- keepout cube))
+ (send keepout :translate #f(0 0 375))
+ (send *co* :add-object keepout :frame-id base-frame-id :object-id "keepout")))
+ (:delete-keepout-collision-object ()
+ (send *co* :delete-object-by-id "keepout"))
+ (:add-ground-collision-object ()
+ (let ((cube (make-cube 200 350 50))
+ (ground (make-cylinder 1000 50)))
+ (send cube :translate #f(-120 0 0))
+ (send ground :translate #f(0 0 -25))
+ (setq ground (body- ground cube))
+ (send ground :translate #f(0 0 -25))
+ (send *co* :add-object ground :frame-id base-frame-id :object-id "ground")))
+ (:delete-ground-collision-object ()
+ (send *co* :delete-object-by-id "ground")))
;; interface for simple base actions
(defmethod fetch-interface
@@ -229,9 +256,9 @@ Example: (send self :gripper :position) => 0.00"
(ros::rate 10)
t)
(:go-pos-unsafe
- (&rest args)
- (send self :put :go-pos-unsafe-no-wait-goal (coerce args float-vector))
- (send self :go-pos-unsafe-wait)
+ (x y d &rest 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]
@@ -256,7 +283,7 @@ Example: (send self :gripper :position) => 0.00"
(forward-p (>= x 0))
(d0 (if forward-p (atan2 y x) (atan2 (- y) (- x))))
(d1 (distance (float-vector 0 0) (float-vector x y)))
- (d2 (shortest-angle (- d d0) 0))
+ (d2 (shortest-angle (- (deg2rad d) d0) 0))
org-cds cur-cds diffrot diffpos err)
(send self :remprop :go-pos-unsafe-no-wait-goal)
@@ -329,11 +356,14 @@ Example: (send self :gripper :position) => 0.00"
d-vel (* (if (>= d-vel 0) 1.0 -1.0) min-rotation-abs-vel))))
(ros::sleep))
t)))
+ (:move-to-wait (&rest args &key (correction nil) &allow-other-keys)
+ (send-super* :move-to-wait :correction correction args))
) ;; fetch-interface (simple base actions)
(defun fetch-init (&optional (create-viewer))
(unless (boundp '*fetch*) (fetch) (send *fetch* :reset-pose))
(unless (ros::ok) (ros::roseus "fetch_eus_interface"))
+ (unless (boundp '*co*) (setq *co* (instance collision-object-publisher :init)))
(unless (boundp '*ri*) (setq *ri* (instance fetch-interface :init)))
(ros::spin-once)
diff --git a/jsk_fetch_robot/fetcheus/test/test-fetch-moveit.l b/jsk_fetch_robot/fetcheus/test/test-fetch-moveit.l
index d9274c0626..24ab545d37 100755
--- a/jsk_fetch_robot/fetcheus/test/test-fetch-moveit.l
+++ b/jsk_fetch_robot/fetcheus/test/test-fetch-moveit.l
@@ -9,6 +9,11 @@
(setq *fetch* (fetch))
(send *fetch* :reset-pose)
+
+(deftest test-fetch-state-worldcoords ()
+ (let ((coords (send *ri* :state :worldcoords "base_link")))
+ (assert coords (format nil "failed to get :state :worldcoords" coords))))
+
(deftest test-fetch-moveit ()
(let (tm-0 tm-1)
(setq tm-0 (ros::time-now))
diff --git a/jsk_fetch_robot/jsk_fetch_diagnosis/CMakeLists.txt b/jsk_fetch_robot/jsk_fetch_diagnosis/CMakeLists.txt
index 02f8ce2963..086cd1a48f 100644
--- a/jsk_fetch_robot/jsk_fetch_diagnosis/CMakeLists.txt
+++ b/jsk_fetch_robot/jsk_fetch_diagnosis/CMakeLists.txt
@@ -23,7 +23,7 @@ catkin_package(
CATKIN_DEPENDS message_runtime
)
-install(DIRECTORY scripts
+install(DIRECTORY node_scripts
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
USE_SOURCE_PERMISSIONS
)
diff --git a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt
index 710ed4d32c..a2fa7d1e2e 100644
--- a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt
+++ b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt
@@ -24,6 +24,10 @@ catkin_add_env_hooks(99.jsk_fetch_startup SHELLS bash zsh sh
## Install ##
#############
install(DIRECTORY config launch scripts data
+ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+ USE_SOURCE_PERMISSIONS)
+
+install(FILES jsk_fetch.machine
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
#############
diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml
index 07f1a714ea..43d79040b6 100644
--- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml
+++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml
@@ -97,6 +97,14 @@
+
+
+
+
+
self.max_retry_num:
rospy.logerr("Maximum retry count reached. Give up resetting motors")
return
+ rospy.logwarn("resetting motors")
self.reset_srv()
self.history = history + [stamp]
diff --git a/jsk_robot_common/jsk_robot_startup/CMakeLists.txt b/jsk_robot_common/jsk_robot_startup/CMakeLists.txt
index 7f008428a3..90492f12d5 100644
--- a/jsk_robot_common/jsk_robot_startup/CMakeLists.txt
+++ b/jsk_robot_common/jsk_robot_startup/CMakeLists.txt
@@ -99,7 +99,7 @@ install(DIRECTORY lifelog util launch images config cfg
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
USE_SOURCE_PERMISSIONS)
-install(TARGETS jsk_robot_lifelog ${${PROJET_NAME}_LIFELOG_NODELET_EXECUTABLES}
+install(TARGETS jsk_robot_lifelog joint_states_throttle ${${PROJET_NAME}_LIFELOG_NODELET_EXECUTABLES}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch
index 589f1d8e6e..4d53b2e6e4 100644
--- a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch
+++ b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch
@@ -44,11 +44,14 @@
+
+
+
+ output="screen" respawn="$(arg respawn)" launch-prefix="$(arg launch-prefix)"/>
@@ -57,7 +60,7 @@
@@ -82,7 +85,7 @@
@@ -103,7 +106,7 @@
@@ -125,7 +128,7 @@
@@ -137,7 +140,7 @@
@@ -151,7 +154,7 @@
@@ -163,7 +166,7 @@
@@ -189,7 +192,7 @@
@@ -198,7 +201,7 @@