|
14 | 14 | (:initialize-arm-robot-ros
|
15 | 15 | ()
|
16 | 16 | ;; subscriber
|
17 |
| - (dotimes (i (length (send robot :angle-vector))) |
| 17 | + |
| 18 | + (dotimes (i (+ (length (send robot :angle-vector)) 1)) |
18 | 19 | (ros::subscribe
|
19 |
| - (format nil "/arm_j~d_controller/state" (1+ i)) |
| 20 | + (if (eq i 6) |
| 21 | + (format nil "/gripper_joint_controller/state") |
| 22 | + (format nil "/arm_j~d_controller/state" (1+ i))) |
20 | 23 | dynamixel_msgs::JointState
|
21 | 24 | #'send self :dynamixel-motor-states-callback :groupname groupname))
|
| 25 | + |
22 | 26 | (unless (send self :simulation-modep)
|
23 |
| - ;; services |
| 27 | + ;; services for arm joints |
24 | 28 | (dotimes (i (length (send robot :angle-vector)))
|
25 | 29 | (ros::wait-for-service
|
26 | 30 | (format nil "/arm_j~d_controller/set_compliance_slope" (1+ i)))
|
|
29 | 33 | (ros::wait-for-service
|
30 | 34 | (format nil "/arm_j~d_controller/set_torque_limit" (1+ i)))
|
31 | 35 | )
|
| 36 | + ;; services for gripper joint |
| 37 | + (ros::wait-for-service |
| 38 | + (format nil "/gripper_joint_controller/set_compliance_slope")) |
| 39 | + (ros::wait-for-service |
| 40 | + (format nil "/gripper_joint_controller/torque_enable")) |
| 41 | + (ros::wait-for-service |
| 42 | + (format nil "/gripper_joint_controller/set_torque_limit")) |
32 | 43 | )
|
33 |
| - ;; define actions |
| 44 | + ;; arm controller action |
34 | 45 | (dolist (l (list
|
35 | 46 | (cons :fullbody-controller "fullbody_controller/follow_joint_trajectory")
|
36 |
| - (cons :gripper-controller "gripper_controller/follow_joint_trajectory") |
37 | 47 | ))
|
38 | 48 | (let ((type (car l))
|
39 | 49 | (name (cdr l))
|
|
48 | 58 | control_msgs::followjointtrajectoryaction
|
49 | 59 | :groupname groupname))))
|
50 | 60 | ))
|
| 61 | + |
| 62 | + ;; gripper controller action |
| 63 | + (setq gripper-action (instance ros::simple-action-client :init |
| 64 | + "/gripper_controller/follow_joint_trajectory" |
| 65 | + control_msgs::FollowJointTrajectoryAction |
| 66 | + :groupname groupname)) |
| 67 | + ;; wait for gripper-action server |
| 68 | + (unless (and joint-action-enable (send gripper-action :wait-for-server 3)) |
| 69 | + (setq joint-action-enable nil) |
| 70 | + (ros::ros-warn "~A is not respond, robot-interface is disabled" gripper-action)) |
51 | 71 | )
|
| 72 | + |
52 | 73 | ;; TODO
|
53 | 74 | ;; This method is tempolary code.
|
54 | 75 | ;; dynamixel_controller_manager should publish /dxl_7dof_arm/joint_states
|
|
58 | 79 | (dolist (key '(:position :velocity :effort :name))
|
59 | 80 | ;; neglect /joint_states from turtlebot
|
60 | 81 | (unless (and (cdr (assoc key robot-state))
|
61 |
| - (= (length (send robot :angle-vector)) (length (cdr (assoc key robot-state))))) |
| 82 | + (= (1+ (length (send robot :angle-vector))) (length (cdr (assoc key robot-state))))) |
62 | 83 | (send self :set-robot-state1 key
|
63 | 84 | (if (eq key :name)
|
64 |
| - (make-list (length (send robot :angle-vector))) |
65 |
| - (instantiate float-vector (length (send robot :angle-vector))))))) |
| 85 | + (make-list (1+ (length (send robot :angle-vector)))) |
| 86 | + (instantiate float-vector (1+ (length (send robot :angle-vector)))))))) |
66 | 87 | ;; update values
|
67 | 88 | (dolist (key '(:position :velocity :effort :name))
|
68 | 89 | (setf (elt (cdr (assoc key robot-state)) (1- (elt (send msg :motor_ids) 0)))
|
|
74 | 95 | )
|
75 | 96 | )
|
76 | 97 | )
|
| 98 | + |
77 | 99 | (:fullbody-controller
|
78 | 100 | ()
|
79 | 101 | (list
|
|
82 | 104 | (cons :controller-state "fullbody_controller/state")
|
83 | 105 | (cons :action-type control_msgs::FollowJointTrajectoryAction)
|
84 | 106 | (cons :joint-names (mapcar #'(lambda (n) (if (symbolp n) (symbol-name n) n))
|
85 |
| - (send-all |
86 |
| - (remove-if #'(lambda (x) |
87 |
| - (member x (send robot :gripper :arm :joint-list))) |
88 |
| - (send robot :joint-list)) |
89 |
| - :name) |
| 107 | + (send-all (send robot :joint-list) :name) |
90 | 108 | )))
|
91 | 109 | )
|
92 | 110 | )
|
| 111 | + #| |
93 | 112 | (:gripper-controller
|
94 | 113 | ()
|
95 | 114 | (list
|
|
102 | 121 | )))
|
103 | 122 | )
|
104 | 123 | )
|
| 124 | + |# |
| 125 | + |
105 | 126 | (:default-controller
|
106 | 127 | ()
|
107 | 128 | (send self :fullbody-controller)
|
|
113 | 134 | ;; http://www.besttechnology.co.jp/modules/knowledge/?Dynamixel%E3%82%B3%E3%83%B3%E3%83%88%E3%83%AD%E3%83%BC%E3%83%AB%E3%83%86%E3%83%BC%E3%83%96%E3%83%AB%28DX%2CRX%2CAX%E3%82%B7%E3%83%AA%E3%83%BC%E3%82%BA%E7%94%A8%29#m041ac16
|
114 | 135 | (:set-compliance-slope ;; for one joint
|
115 | 136 | (id slope)
|
116 |
| - "Set compliance slope for one joint. id should be 1-7. slope is 32 by default." |
| 137 | + "Set compliance slope for one joint. id should be 1-6. slope is 32 by default." |
117 | 138 | (ros::service-call
|
118 |
| - (format nil "/arm_j~d_controller/set_compliance_slope" id) |
| 139 | + (if (eq id 7) |
| 140 | + (format nil "/gripper_joint_controller/set_compliance_slope") |
| 141 | + (format nil "/arm_j~d_controller/set_compliance_slope" id)) |
119 | 142 | (instance dynamixel_controllers::setcomplianceslopeRequest :init
|
120 | 143 | :slope (round slope)))
|
121 | 144 | )
|
|
129 | 152 | (id torque-limit)
|
130 | 153 | "Set torque limit for one joint. id should be 1-7. torque-limit should be within [0, 1]."
|
131 | 154 | (ros::service-call
|
132 |
| - (format nil "/arm_j~d_controller/set_torque_limit" id) |
| 155 | + (if (eq id 7) |
| 156 | + (format nil "/gripper_joint_controller/set_torque_limit" id) |
| 157 | + (format nil "/arm_j~d_controller/set_torque_limit" id)) |
133 | 158 | (instance dynamixel_controllers::SetTorqueLimitRequest :init
|
134 | 159 | :torque_limit torque-limit)))
|
135 | 160 | (:torque-enable
|
136 | 161 | (id torque-enable)
|
137 | 162 | "Configure joint torque mode for one joint. id sohuld be 1-7. If torque-enable is t, move to torque control mode, otherwise, move to joint positoin mode."
|
138 | 163 | (ros::service-call
|
139 |
| - (format nil "/arm_j~d_controller/torque_enable" id) |
| 164 | + (if (eq id 7) |
| 165 | + (format nil "/gripper_joint_controller/torque_enable" id) |
| 166 | + (format nil "/arm_j~d_controller/torque_enable" id)) |
140 | 167 | (instance dynamixel_controllers::TorqueEnableRequest :init
|
141 | 168 | :torque_enable torque-enable)))
|
142 | 169 |
|
|
152 | 179 | (:servo-on-all
|
153 | 180 | ()
|
154 | 181 | "Servo On for all joints."
|
155 |
| - (dotimes (i (length (send robot :angle-vector))) |
| 182 | + (dotimes (i (+ (length (send robot :angle-vector)) 1)) |
156 | 183 | (send self :servo-on-off (1+ i) t)))
|
157 | 184 | (:servo-off-all
|
158 | 185 | ()
|
159 | 186 | "Servo Off for all joints."
|
160 |
| - (dotimes (i (length (send robot :angle-vector))) |
| 187 | + (dotimes (i (+ (length (send robot :angle-vector)) 1)) |
161 | 188 | (send self :servo-on-off (1+ i) nil)))
|
162 | 189 | (:servo-on-off
|
163 | 190 | (id on/off) ;; id = 1-7, t -> "On", nil -> "Off"
|
|
166 | 193 | (if on/off ;; just for servo off->on
|
167 | 194 | (send self :set-torque-limit id 1.0)))
|
168 | 195 |
|
| 196 | + (:move-gripper |
| 197 | + (pos &key (tm 1000) (wait t)) |
| 198 | + (unless joint-action-enable |
| 199 | + (send (send robot :gripper_joint) :joint-angle pos ) |
| 200 | + (send self :publish-joint-state) |
| 201 | + (if viewer (send self :draw-objects)) |
| 202 | + (return-from :move-gripper nil)) |
| 203 | + ;; for real robot |
| 204 | + (let* ((goal (send gripper-action :make-goal-instance)) |
| 205 | + (goal-points nil) |
| 206 | + (joint-names (list (send (send robot :gripper_joint) :name)))) |
| 207 | + (send goal :header :seq 1) |
| 208 | + (send goal :header :stamp (ros::time-now)) |
| 209 | + |
| 210 | + (send goal :goal :trajectory :joint_names joint-names) |
| 211 | + (send goal :goal :trajectory :header :stamp (ros::time-now)) |
| 212 | + |
| 213 | + (push (instance trajectory_msgs::JointTrajectoryPoint |
| 214 | + :init |
| 215 | + :positions (float-vector (deg2rad pos)) |
| 216 | + :velocities (float-vector 0) |
| 217 | + :time_from_start (ros::time (/ tm 1000.0))) |
| 218 | + goal-points) |
| 219 | + |
| 220 | + (send self :spin-once) |
| 221 | + (send goal :goal :trajectory :points goal-points) |
| 222 | + (send gripper-action :send-goal goal) |
| 223 | + ) |
| 224 | + #| |
| 225 | + (send self :send-ros-controller |
| 226 | + gripper-action (list (send (send robot :gripper_joint) :name)) ;; action server and joint-names |
| 227 | + 0 ;; start time |
| 228 | + (list |
| 229 | + (list (float-vector pos) ;; positions |
| 230 | + (instantiate float-vector 1) ;; velocities |
| 231 | + (/ tm 1000.0)))) |
| 232 | + |# |
| 233 | + (if wait (send gripper-action :wait-for-result)) |
| 234 | + ) |
| 235 | + |
169 | 236 | ;; 把持モード開始メソッド
|
170 | 237 | (:start-grasp
|
171 |
| - (&optional (arm :arm) &key ((:gain g) 0.5) ((:objects objs) objects)) |
| 238 | + (&key ((:gain g) 0.5)) |
172 | 239 | "Start grasp mode."
|
173 |
| - (send self :set-compliance-slope 7 1023) |
174 |
| - (send self :set-torque-limit 7 g) |
175 |
| - (send robot :gripper arm :angle-vector |
176 |
| - (send-all (send robot :gripper arm :joint-list) :min-angle)) |
177 |
| - (send self :angle-vector (send robot :angle-vector) 1000 :gripper-controller) |
178 |
| - (send self :wait-interpolation :gripper-controller) |
| 240 | + (unless (send self :simulation-modep) |
| 241 | + (send self :set-compliance-slope 7 1023) |
| 242 | + (send self :set-torque-limit 7 g)) |
| 243 | + (send self :move-gripper (send (send robot :gripper_joint) :min-angle) :tm 1000 :wait t) |
179 | 244 | (send self :state)
|
180 |
| - (send robot :gripper arm :angle-vector |
181 |
| - (mapcar #'(lambda (x) (- x 5)) (send-all (send robot :gripper arm :joint-list) :joint-angle))) ;; 5[deg] |
182 |
| - (send self :angle-vector (send robot :angle-vector) 200 :gripper-controller) |
183 |
| - (send self :wait-interpolation :gripper-controller) |
| 245 | + (send robot :gripper :arm :joint-angle (- (send robot :gripper :arm :joint-angle) 5)) ;; 5[deg] |
| 246 | + (send self :move-gripper (send robot :gripper :arm :joint-angle) :tm 200 :wait t) |
184 | 247 | )
|
| 248 | + |
185 | 249 | ;; 把持モード停止メソッド
|
186 | 250 | (:stop-grasp
|
187 |
| - (&optional (arm :arm) &key (wait nil)) |
| 251 | + () |
188 | 252 | "Stop grasp mode."
|
189 |
| - (send robot :gripper arm :angle-vector |
190 |
| - (send-all (send robot :gripper arm :joint-list) :max-angle)) |
191 |
| - (send self :angle-vector (send robot :angle-vector) 1000 :gripper-controller) |
192 |
| - (send self :set-compliance-slope 7 32) |
193 |
| - (send self :set-torque-limit 7 1.0) |
194 |
| - (send self :wait-interpolation :gripper-controller) |
| 253 | + (send self :move-gripper (send (send robot :gripper_joint) :max-angle) :tm 1000 :wait t) |
| 254 | + (unless (send self :simulation-modep) |
| 255 | + (send self :set-compliance-slope 7 32) |
| 256 | + (send self :set-torque-limit 7 1.0)) |
195 | 257 | )
|
196 | 258 | )
|
197 | 259 | )
|
0 commit comments