Skip to content

Commit 30f837b

Browse files
authored
Merge pull request #244 from tongtybj/dxl_arm
Update the robot model of dxl_7dof_arm
2 parents f5133c4 + f696fdb commit 30f837b

File tree

8 files changed

+151
-58
lines changed

8 files changed

+151
-58
lines changed

dxl_armed_turtlebot/euslisp/dxl-armed-turtlebot-interface.l

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414
;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
1515
(defclass dxl-armed-turtlebot-interface
1616
:super robot-interface
17-
:slots ())
17+
:slots (gripper-action))
1818

1919
(eval `(defmethod dxl-armed-turtlebot-interface
2020
;; dxl-7dof-arm-interface, turtlebot-interfaceのメソッドをそれぞれdefmethodする
@@ -48,4 +48,4 @@
4848
(send *irtviewer* :change-background #f(0.9 0.9 0.9))
4949
(send *irtviewer* :draw-objects)
5050
)
51-
(warn ";; (dxl-armed-turtlebot-init) ;; for initialize ~%")
51+
(warn ";; (dxl-armed-turtlebot-init) ;; for initialize ~%")

dxl_armed_turtlebot/euslisp/dxl-armed-turtlebot.l

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,8 @@
6363
(send self :method-copying "-pose")
6464
(send self :method-copying "_joint")
6565
(send self :method-copying "inverse-kinematics" t)
66+
(send self :method-copying "gripper" t)
67+
(send self :method-copying "arm" t)
6668
t))
6769
(:method-copying
6870
(substr &optional (use-args nil))
@@ -79,10 +81,12 @@
7981
,(if use-args `(send* arm-robot ,me args) `(send arm-robot ,me))
8082
)
8183
))
82-
)))
84+
)
85+
methods))
86+
8387
;; limbs
84-
(:arm (&rest args)
85-
(unless args (setq args (list nil))) (send* self :limb :rarm args))
88+
;;(:arm (&rest args)
89+
;;(unless args (setq args (list nil))) (send* self :limb :rarm args))
8690
)
8791

8892
;; アーム台車モデル生成関数

dynamixel_7dof_arm/config/dynamixel_joint_controllers.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -76,12 +76,12 @@ arm_j6_controller:
7676
min: 0
7777
max: 1023
7878

79-
arm_j7_controller:
79+
gripper_joint_controller:
8080
controller:
8181
package: dynamixel_controllers
8282
module: joint_position_controller
8383
type: JointPositionController
84-
joint_name: arm_joint7
84+
joint_name: gripper_joint
8585
joint_speed: 2.0
8686
motor:
8787
id: 7

dynamixel_7dof_arm/euslisp/dxl-7dof-arm-interface-common.l

Lines changed: 99 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -14,13 +14,17 @@
1414
(:initialize-arm-robot-ros
1515
()
1616
;; subscriber
17-
(dotimes (i (length (send robot :angle-vector)))
17+
18+
(dotimes (i (+ (length (send robot :angle-vector)) 1))
1819
(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)))
2023
dynamixel_msgs::JointState
2124
#'send self :dynamixel-motor-states-callback :groupname groupname))
25+
2226
(unless (send self :simulation-modep)
23-
;; services
27+
;; services for arm joints
2428
(dotimes (i (length (send robot :angle-vector)))
2529
(ros::wait-for-service
2630
(format nil "/arm_j~d_controller/set_compliance_slope" (1+ i)))
@@ -29,11 +33,17 @@
2933
(ros::wait-for-service
3034
(format nil "/arm_j~d_controller/set_torque_limit" (1+ i)))
3135
)
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"))
3243
)
33-
;; define actions
44+
;; arm controller action
3445
(dolist (l (list
3546
(cons :fullbody-controller "fullbody_controller/follow_joint_trajectory")
36-
(cons :gripper-controller "gripper_controller/follow_joint_trajectory")
3747
))
3848
(let ((type (car l))
3949
(name (cdr l))
@@ -48,7 +58,18 @@
4858
control_msgs::followjointtrajectoryaction
4959
:groupname groupname))))
5060
))
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))
5171
)
72+
5273
;; TODO
5374
;; This method is tempolary code.
5475
;; dynamixel_controller_manager should publish /dxl_7dof_arm/joint_states
@@ -58,11 +79,11 @@
5879
(dolist (key '(:position :velocity :effort :name))
5980
;; neglect /joint_states from turtlebot
6081
(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)))))
6283
(send self :set-robot-state1 key
6384
(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))))))))
6687
;; update values
6788
(dolist (key '(:position :velocity :effort :name))
6889
(setf (elt (cdr (assoc key robot-state)) (1- (elt (send msg :motor_ids) 0)))
@@ -74,6 +95,7 @@
7495
)
7596
)
7697
)
98+
7799
(:fullbody-controller
78100
()
79101
(list
@@ -82,14 +104,11 @@
82104
(cons :controller-state "fullbody_controller/state")
83105
(cons :action-type control_msgs::FollowJointTrajectoryAction)
84106
(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)
90108
)))
91109
)
92110
)
111+
#|
93112
(:gripper-controller
94113
()
95114
(list
@@ -102,6 +121,8 @@
102121
)))
103122
)
104123
)
124+
|#
125+
105126
(:default-controller
106127
()
107128
(send self :fullbody-controller)
@@ -113,9 +134,11 @@
113134
;; 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
114135
(:set-compliance-slope ;; for one joint
115136
(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."
117138
(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))
119142
(instance dynamixel_controllers::setcomplianceslopeRequest :init
120143
:slope (round slope)))
121144
)
@@ -129,14 +152,18 @@
129152
(id torque-limit)
130153
"Set torque limit for one joint. id should be 1-7. torque-limit should be within [0, 1]."
131154
(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))
133158
(instance dynamixel_controllers::SetTorqueLimitRequest :init
134159
:torque_limit torque-limit)))
135160
(:torque-enable
136161
(id torque-enable)
137162
"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."
138163
(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))
140167
(instance dynamixel_controllers::TorqueEnableRequest :init
141168
:torque_enable torque-enable)))
142169

@@ -152,12 +179,12 @@
152179
(:servo-on-all
153180
()
154181
"Servo On for all joints."
155-
(dotimes (i (length (send robot :angle-vector)))
182+
(dotimes (i (+ (length (send robot :angle-vector)) 1))
156183
(send self :servo-on-off (1+ i) t)))
157184
(:servo-off-all
158185
()
159186
"Servo Off for all joints."
160-
(dotimes (i (length (send robot :angle-vector)))
187+
(dotimes (i (+ (length (send robot :angle-vector)) 1))
161188
(send self :servo-on-off (1+ i) nil)))
162189
(:servo-on-off
163190
(id on/off) ;; id = 1-7, t -> "On", nil -> "Off"
@@ -166,32 +193,67 @@
166193
(if on/off ;; just for servo off->on
167194
(send self :set-torque-limit id 1.0)))
168195

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+
169236
;; 把持モード開始メソッド
170237
(:start-grasp
171-
(&optional (arm :arm) &key ((:gain g) 0.5) ((:objects objs) objects))
238+
(&key ((:gain g) 0.5))
172239
"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)
179244
(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)
184247
)
248+
185249
;; 把持モード停止メソッド
186250
(:stop-grasp
187-
(&optional (arm :arm) &key (wait nil))
251+
()
188252
"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))
195257
)
196258
)
197259
)

dynamixel_7dof_arm/euslisp/dxl-7dof-arm-interface.l

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
1414
(defclass dxl-7dof-arm-interface
1515
:super robot-interface
16-
:slots ())
16+
:slots (gripper-action))
1717

1818
(eval `(defmethod dxl-7dof-arm-interface
1919
;; dxl-7dof-arm-interfaceのメソッドをdefmethodする

0 commit comments

Comments
 (0)