Skip to content

Commit 76a2ec6

Browse files
authored
Merge pull request #1405 from tkmtnt7000/PR-fetch-add-servo-off-master
[Fetch] add servo-off method to fetch-interface.l
2 parents 0b55748 + 1f6d329 commit 76a2ec6

File tree

2 files changed

+94
-2
lines changed

2 files changed

+94
-2
lines changed

jsk_fetch_robot/README.md

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -182,6 +182,15 @@ roslaunch jsk_fetch_gazebo_demo demo.launch
182182
(send *fetch* :rarm :shoulder-y :joint-angle 75)
183183
```
184184

185+
- Servo on and off. Able to choose servo on and off part respectively.
186+
187+
```lisp
188+
(send *ri* :servo-off) ;; arm, gripper and head servos off
189+
(send *ri* :servo-off :arm t :gripper nil :head nil) ;; arm servo off
190+
(send *ri* :servo-on) ;; arm, gripper and head servos on
191+
(send *ri* :servo-on :arm t :gripper nil :head nil :time 80) ;; arm servo on in 80[msec]
192+
```
193+
185194
### Gripper Control
186195

187196
- Grasp object

jsk_fetch_robot/fetcheus/fetch-interface.l

Lines changed: 85 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,10 +4,11 @@
44

55
(ros::load-ros-package "fetcheus")
66
(ros::load-ros-package "fetch_driver_msgs")
7+
(ros::load-ros-package "robot_controllers_msgs")
78

89
(defclass fetch-interface
910
:super robot-move-base-interface
10-
:slots (gripper-action moveit-robot)
11+
:slots (gripper-action moveit-robot fetch-controller-action)
1112
)
1213

1314
(defmethod fetch-interface
@@ -32,6 +33,10 @@
3233
(send self :delete-ground-collision-object)
3334
(send self :add-keepout-collision-object)
3435
(send self :add-ground-collision-object))
36+
(setq fetch-controller-action
37+
(instance ros::simple-action-client :init
38+
"/query_controller_states"
39+
robot_controllers_msgs::QueryControllerStatesAction))
3540
))
3641
(:state (&rest args)
3742
"We do not have :wait-until-update option for :state :worldcoords.
@@ -265,7 +270,85 @@ Example: (send self :gripper :position) => 0.00"
265270
:touch-links nil)))
266271
(:delete-ground-collision-object ()
267272
(send *co* :delete-attached-object-by-id "ground")
268-
(send *co* :delete-object-by-id "ground")))
273+
(send *co* :delete-object-by-id "ground"))
274+
(:servo-off (&key (arm t) (gripper t) (head t))
275+
"
276+
Turn servo off for arm/gripper/head motors
277+
Args:
278+
- key
279+
- arm: If you do not want to servo off the arm, set nil (default: t)
280+
- gripper: If you do not want to servo off the grippper, set nil (default: t)
281+
- head: If you do not want to servo off the head, set nil (default: t)
282+
Examples:
283+
(send self :servo-off) ;; arm, gripper and head servos off
284+
(send self :servo-off :arm t :gripper nil :head nil) ;; arm servo off
285+
"
286+
(let ((goal-servo-off (instance robot_controllers_msgs::QueryControllerStatesGoal :init))
287+
(goal-gripper-servo-off (instance control_msgs::GripperCommandGoal :init))
288+
(state nil) (update-list nil)
289+
(gravity-comp (list "arm_controller/gravity_compensation"))
290+
(arm-controller (list "arm_controller/follow_joint_trajectory"
291+
"arm_with_torso_controller/follow_joint_trajectory"
292+
"torso_controller/follow_joint_trajectory"))
293+
(head-controller (list "head_controller/follow_joint_trajectory"
294+
"head_controller/point_head")))
295+
(when (or arm head)
296+
(setq update-list (send goal-servo-off :updates))
297+
(when arm
298+
(ros::ros-info "arm servo off")
299+
;; start gravity compensation
300+
(dolist (controller gravity-comp)
301+
(setq state (instance robot_controllers_msgs::ControllerState :init))
302+
(send state :name controller)
303+
(send state :state 1) ;; running
304+
(push state update-list))
305+
;; stop arm controllers
306+
(dolist (controller arm-controller)
307+
(setq state (instance robot_controllers_msgs::ControllerState :init))
308+
(send state :name controller)
309+
(send state :state 0) ;; stopping
310+
(push state update-list)))
311+
(when head
312+
;; stop head controllers
313+
(ros::ros-info "head servo off")
314+
(dolist (controller head-controller)
315+
(setq state (instance robot_controllers_msgs::ControllerState :init))
316+
(send state :name controller)
317+
(send state :state 0) ;; stopping
318+
(push state update-list)))
319+
(send goal-servo-off :updates update-list)
320+
(send fetch-controller-action :send-goal goal-servo-off))
321+
(when gripper
322+
;; disable gripper torque
323+
(ros::ros-info "gripper servo off")
324+
(send (send goal-gripper-servo-off :command) :max_effort -1.0)
325+
(send gripper-action :send-goal goal-gripper-servo-off))))
326+
(:servo-on (&key (arm t) (gripper t) (head t) (time 200))
327+
"
328+
Turn servo on for arm/gripper/head motors
329+
Args:
330+
- key:
331+
- arm: If you do not want to servo on the arm, set nil (default: t)
332+
- gripper: If you do not want to servo on the grippper, set nil (default: t)
333+
- head: If you do not want to servo on the head, set nil (default: t)
334+
- time: [msec] duration to turn servo on,
335+
experimentally the minimal duration is about 60[msec] (default: 200)
336+
Examples:
337+
(send self :servo-on) ;; arm, gripper and head servos on
338+
(send self :servo-on :arm nil :gripper nil :head t :time 80) ;; head servo on in 80[msec]
339+
"
340+
;; the reason why :servo-off and :servo-on has different implementation is in the following issue
341+
;; https://github.com/fetchrobotics/robot_controllers/issues/72
342+
(when arm
343+
(ros::ros-info "arm servo on")
344+
(send self :angle-vector (send self :state :potentio-vector) time :arm-controller)
345+
(send self :angle-vector (send self :state :potentio-vector) time :torso-controller))
346+
(when head
347+
(ros::ros-info "head servo on")
348+
(send self :angle-vector (send self :state :potentio-vector) time :head-controller))
349+
(when gripper
350+
(ros::ros-info "gripper servo on")
351+
(send self :go-grasp :pos (send self :gripper :position)))))
269352

270353
;; interface for simple base actions
271354
(defmethod fetch-interface

0 commit comments

Comments
 (0)