-
Notifications
You must be signed in to change notification settings - Fork 3
/
move.py
executable file
·158 lines (124 loc) · 4.34 KB
/
move.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
#!/usr/bin/env python
from __future__ import print_function
import rospy
import tf
import math
import argparse
from sensor_msgs.msg import Joy
from geometry_msgs.msg import Twist
from geometry_msgs.msg import PoseStamped
msg = """
"""
class MovePub:
def __init__(self, name=''):
self.joy_pub_ = rospy.Publisher('%sjoy'%(name), Joy, queue_size = 10)
self.cmd_pub_ = rospy.Publisher('%scmd_vel'%(name), Twist, queue_size = 10)
self.stop_ = rospy.get_param("~stop", 0.5)
self.trans_x = 0.0
self.trans_y = 0.0
self.trans_z = 0.0
self.rot_x = 0.0
self.rot_y = 0.0
self.rot_z = 0.0
self.rot_w = 1.0
self.tm = None
self.rate = rospy.Rate(100)
def stop_pub(self):
msg = Joy()
msg.axes = [0]*8
msg.buttons = [0]*11
self.joy_pub_.publish(msg)
cmd = Twist()
self.cmd_pub_.publish(cmd)
def move_pub(self, trans, rot):
msg = Joy()
msg.axes = [0]*8
msg.buttons = [0]*11
# print('move: %f %f'%(trans, rot))
if trans > 0.0:
msg.axes[1] = -1
elif trans < 0.0:
msg.axes[1] = 1
if rot > 0.0:
msg.axes[0] = -1
elif rot < 0.0:
msg.axes[0] = 1
self.joy_pub_.publish(msg)
cmd = Twist()
if trans != 0.0:
cmd.linear.x = 4.0 * trans / math.fabs(trans)
if rot != 0.0:
cmd.angular.z = 1.5 * rot / math.fabs(rot)
self.cmd_pub_.publish(cmd)
def move(self, x_trans = 0.0 , z_rot = 0.0):
origin_pos = (self.trans_x, self.trans_y, self.trans_z)
origin_rot = (self.rot_w, self.rot_x, self.rot_y, self.rot_z)
#print(origin_pos)
for i in range(20): ## waiting enable publishing (why needed??)
self.rate.sleep()
self.move_pub(x_trans, z_rot)
cntr = 0
while True:
self.rate.sleep()
pos = (self.trans_x, self.trans_y, self.trans_z)
rot = (self.rot_w, self.rot_x, self.rot_y, self.rot_z)
#print(pos)
diff_pos = [pos[0] - origin_pos[0], pos[1] - origin_pos[1], pos[2] - origin_pos[2]]
diff_len = math.sqrt(diff_pos[0] * diff_pos[0] + diff_pos[1] * diff_pos[1] + diff_pos[2] * diff_pos[2])
diff_rot = math.atan2(rot[3], rot[0]) - math.atan2(origin_rot[3], origin_rot[0])
if diff_rot > math.pi:
diff_rot = diff_rot - math.pi
if diff_rot < - math.pi:
diff_rot = diff_rot + math.pi
diff_rot = math.sqrt(diff_rot * diff_rot)
### debug print
if cntr %10 == 0:
print('trans:%5.2f rot:%5.2f'%(diff_len, diff_rot))
cntr = cntr + 1
if x_trans == 0.0 or diff_len > math.fabs(x_trans):
if z_rot == 0.0 or diff_rot > math.fabs(z_rot):
print('trans:%5.2f rot:%5.2f'%(diff_len, diff_rot))
break
self.stop_pub()
def callback(self, msg):
self.tm = msg.header.stamp
##fm = msg.header.frame_id
self.trans_x = msg.pose.position.x
self.trans_y = msg.pose.position.y
self.trans_z = msg.pose.position.z
self.rot_x = msg.pose.orientation.x
self.rot_y = msg.pose.orientation.y
self.rot_z = msg.pose.orientation.z
self.rot_w = msg.pose.orientation.w
def wait_first_callback(self):
while not self.tm:
self.rate.sleep()
if __name__=="__main__":
### parser section
parser = argparse.ArgumentParser(description='call trajectory action by PoseSeq')
parser.add_argument('-N', '--name', default = None, type=str)
parser.add_argument('--trans', default = None, type=str)
parser.add_argument('--rot', default = None, type=str)
args = parser.parse_args()
name = args.name
if not name:
name = ''
else:
name = name + '/'
trans = args.trans
if not trans:
trans = 0.0
else:
trans = float(trans)
rot = args.rot
if not rot:
rot = 0.0
else:
rot = float(rot)
### ROS section
rospy.init_node('move_sample')
mv = MovePub(name)
rospy.Subscriber('%sground_truth_pose'%(name), PoseStamped, mv.callback)
mv.wait_first_callback()
mv.move(trans, rot)
##rospy.spin()