-
Notifications
You must be signed in to change notification settings - Fork 3
/
toggle_trajectory_controll.py
executable file
·184 lines (149 loc) · 5.01 KB
/
toggle_trajectory_controll.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
#!/usr/bin/env python
import rospy
import actionlib
from control_msgs.msg import (
FollowJointTrajectoryAction,
FollowJointTrajectoryGoal,
JointTrajectoryControllerState,
)
from control_msgs.srv import (
QueryTrajectoryState
)
from trajectory_msgs.msg import (
JointTrajectoryPoint,
)
from std_srvs.srv import (
Empty,
)
import yaml
import argparse
class SingleTrajectory:
def __init__(self, namespace='AizuSpiderAA'):
self.act_ = actionlib.SimpleActionClient(
'%s/fullbody_controller/follow_joint_trajectory'%(namespace),
FollowJointTrajectoryAction,
)
self.act_.wait_for_server(rospy.Duration(10.0))
self.sub_ = rospy.Subscriber('%s/fullbody_controller/state'%(namespace),
JointTrajectoryControllerState, self.state_callback)
self.finish_action_ = False
def go_(self):
state_srv = rospy.ServiceProxy('/AizuSpiderAA/fullbody_controller/query_state',
QueryTrajectoryState)
res = state_srv(rospy.Time.now())
names = res.name
positions = res.position
goal = FollowJointTrajectoryGoal()
goal.trajectory.joint_names = names
goal.trajectory.points = []
p = JointTrajectoryPoint()
p.time_from_start = rospy.Duration(0.1)
p.positions = positions
goal.trajectory.points.append(p)
goal.trajectory.header.stamp = rospy.Time.now() + rospy.Duration(0.01)
print(goal.trajectory)
self.act_.send_goal(goal, feedback_cb=self.feedback)
self.act_.wait_for_result(rospy.Duration(0.2))
self.finish_action_ = True
def state_callback(self, msg):
print('callback')
## shutdown self
self.sub_.unregister()
##
names = msg.joint_names
#positions = msg.desired.positions
positions = msg.actual.positions
goal = FollowJointTrajectoryGoal()
goal.trajectory.joint_names = names
goal.trajectory.points = []
p = JointTrajectoryPoint()
p.time_from_start = rospy.Duration(0.1)
p.positions = positions
goal.trajectory.points.append(p)
goal.trajectory.header.stamp = rospy.Time.now() + rospy.Duration(0.1)
print(goal.trajectory)
self.act_.send_goal(goal, feedback_cb=self.feedback)
self.act_.wait_for_result(rospy.Duration(0.2))
self.finish_action_ = True
def feedback(self, msg):
pass
def call(self, ref_list, offset = 0.0):
'''ref_list = [ [tm, joints, q], ... ]'''
goal = FollowJointTrajectoryGoal()
goal.trajectory.joint_names = ['FR_FLIPPER', 'FL_FLIPPER', 'BR_FLIPPER', 'BL_FLIPPER',
'SHOULDER', 'ARM', 'FOREARM', 'WRIST1', 'WRIST2', 'HAND',
'FINGER1', 'FINGER2', 'FINGER3', ]
goal.trajectory.points = []
for ref in ref_list:
p = JointTrajectoryPoint()
p.time_from_start = rospy.Duration(ref[0] + offset)
qlst = []
q = ref[2]
for j in ref[1]:
qlst.append(q[j])
p.positions = qlst
goal.trajectory.points.append(p)
goal.trajectory.header.stamp = rospy.Time.now() + rospy.Duration(0.01)
print(goal.trajectory)
self.act_.send_goal(goal, feedback_cb=self.feedback)
def wait(self, tm=rospy.Duration(10)):
self.act_.wait_for_result(tm)
# index_map = {
# 0: 'FR_FLIPPER',
# 1: 'FL_FLIPPER',
# 2: 'BR_FLIPPER',
# 3: 'BL_FLIPPER',
# 4: 'SHOULDER',
# 5: 'ARM',
# 6: 'FOREARM',
# 7: 'WRIST1',
# 8: 'WRIST2',
# 9: 'HAND',
# 10: 'FINGER1',
# 11: 'FINGER2',
# 12: 'FINGER3',
# }
index_lst = [
'FR_FLIPPER',
'FL_FLIPPER',
'BR_FLIPPER',
'BL_FLIPPER',
'SHOULDER',
'ARM',
'FOREARM',
'WRIST1',
'WRIST2',
'HAND',
'FINGER1',
'FINGER2',
'FINGER3',
]
if __name__ == '__main__':
parser = argparse.ArgumentParser(description='call trajectory action by PoseSeq')
parser.add_argument('-N', '--name', default = None, type=str)
parser.add_argument('--wait', default = None, type=str)
rospy.init_node('toggle_trajectory_controll', anonymous=True)
args = parser.parse_args()
name = args.name
if not name:
name = 'AizuSpiderAA'
wait_tm = args.wait
if not wait_tm:
wait_tm = 1.0
else:
wait_tm = float(wait_tm)
sg = SingleTrajectory(namespace=name)
start = rospy.Time.now()
while not sg.finish_action_:
now = rospy.Time.now()
if (now.to_sec() - start.to_sec()) > 3.0:
print("timeout")
exit(1)
rospy.wait_for_service('%s/toggle_controller'%(name))
try:
toggle_srv = rospy.ServiceProxy('%s/toggle_controller'%(name), Empty)
res = toggle_srv()
except rospy.ServiceException, e:
print "Service call failed: %s"%e
exit(1)
print("finish")