-
Notifications
You must be signed in to change notification settings - Fork 0
/
test_3.py
378 lines (310 loc) · 12.6 KB
/
test_3.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
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
#!usr/env/bin python
import numpy as np
import math
import matplotlib.pyplot as plt
import argparse
import sys
import rospy
import baxter_interface
# import messages
from geometry_msgs.msg import (
PoseStamped,
Pose,
Point,
Quaternion,
)
from std_msgs.msg import Header
# import service
from baxter_core_msgs.srv import (
SolvePositionIK,
SolvePositionIKRequest,
# The two modules are local ignore the error
from point_2d_my import Point
from line_2d_my import Line
from polygon_my import Polygon
ATTRACTION_COEFFICIENT = 5
REPULSIVE_COEFFICIENT = 60
REPULSIVE_RANGE = 50
STEP_SIZE = 0.1
TOTAL_STEP = 10000
TARGET_RANGE = 0.5
INITIAL_DISTANCE_VALUE = 1000
REPULSIVE_POLY_MULTIPLIER = 3
ALPHA = 0.2
def closest_point_to_line(point_test, line_point_1, line_point_2):
line_temp_list = line_point_1.find_line_point_to_point(line_point_2)
line_temp = Line(line_temp_list[0], line_temp_list[1], line_temp_list[2])
# line_temp.show_line_function()
# line_temp.plot_line()
orthogonal_line = line_temp.orthogonal_line_cross_point(point_test)
# orthogonal_line.plot_line()
# orthogonal_line.show_line_function()
# orthogonal_line.plot_line()
# orthogonal_line = Line(orthogonal_line_list[0], orthogonal_line_list[1], orthogonal_line_list[2])
projection_point_list = line_temp.interception_between_two_lines(orthogonal_line)
projection_point = Point(projection_point_list[0][0], projection_point_list[1][0])
# projection_point.plot_point()
# projection_point.show_value()
# obstacle_point = Point(0, 0)
if line_temp.check_point_on_line(point_test):
if (line_point_1.x <= point_test.x <= line_point_2.x or line_point_2.x <= point_test.x <= line_point_2.x) and\
(line_point_1.y <= point_test.y <= line_point_2.y or line_point_2.y <= point_test.y <= line_point_2.y):
obstacle_point = Point(point_test.x, point_test.y)
else:
distance_point_1 = point_test.find_distance_between_points(line_point_1)
distance_point_2 = point_test.find_distance_between_points(line_point_2)
if distance_point_1 < distance_point_2:
obstacle_point = Point(line_point_1.x, line_point_1.y)
else:
obstacle_point = Point(line_point_2.x, line_point_2.y)
elif (line_point_1.x - ALPHA <= projection_point.x <= line_point_2.x + ALPHA or
line_point_1.x + ALPHA >= projection_point.x >= line_point_2.x - ALPHA) and\
(line_point_1.y - ALPHA <= projection_point.y <= line_point_2.y + ALPHA or
line_point_1.y + ALPHA >= projection_point.y >= line_point_2.y - ALPHA):
obstacle_point = Point(projection_point.x, projection_point.y)
else:
distance_point_1 = point_test.find_distance_between_points(line_point_1)
distance_point_2 = point_test.find_distance_between_points(line_point_2)
if distance_point_1 < distance_point_2:
obstacle_point = Point(line_point_1.x, line_point_1.y)
else:
obstacle_point = Point(line_point_2.x, line_point_2.y)
return obstacle_point
def closest_point_to_obstacle(point_test, polygon):
ref_point = []
distance = INITIAL_DISTANCE_VALUE
for n in range(polygon.get_length() + 1):
ref_point.append(n % polygon.get_length())
closest_point_on_obstacle = Point(0, 0)
for n in range(polygon.get_length()):
# line_temp = polygon[n].find_line_point_to_point(polygon[n + 1])
# distance.append(point_test, line_temp)
print(ref_point[n], ref_point[n+1])
point_obstacle = closest_point_to_line(point_test, polygon.poly[ref_point[n]], polygon.poly[ref_point[n + 1]])
if point_test.find_distance_between_points(point_obstacle) < distance:
distance = point_test.find_distance_between_points(point_obstacle)
closest_point_on_obstacle.x = point_obstacle.x
closest_point_on_obstacle.y = point_obstacle.y
return closest_point_on_obstacle
def attraction_force(point_to_test, point_goal):
vector_magnitude = point_to_test.find_distance_between_points(point_goal)
attraction_vector = Point(point_goal.x - point_to_test.x, point_goal.y - point_to_test.y)
attraction_vector.scale_point(ATTRACTION_COEFFICIENT / vector_magnitude)
return attraction_vector
def repulsive_force(point_to_test, point_obstacle, polygon_centroid):
distance_to_obstacle = point_to_test.find_distance_between_points(point_obstacle)
distance_to_center = point_to_test.find_distance_between_points(polygon_centroid)
repulsive_vector = Point(0, 0)
abs_distance = distance_to_center - distance_to_obstacle
if distance_to_center <= REPULSIVE_RANGE:
repulsive_magnitude = (0.5*REPULSIVE_COEFFICIENT)*(1/(distance_to_center-3)**2)
# *(1/abs_distance**2)
vector_magnitude = point_to_test.find_distance_between_points(polygon_centroid)
repulsive_vector.set_x((point_to_test.x - polygon_centroid.x) * repulsive_magnitude / vector_magnitude)
repulsive_vector.set_y((point_to_test.y - polygon_centroid.y) * repulsive_magnitude / vector_magnitude)
return repulsive_vector
def total_potential_force(att_vector, rep_vector):
total_vector = Point(att_vector.x + rep_vector.x, att_vector.y + att_vector.y)
return total_vector
def potential_get_path(polygon, point_start, point_goal, polygon_centroid):
path = [Point(point_start.x, point_start.y)]
point_current = Point(point_start.x, point_start.y)
step = 0
while point_current.find_distance_between_points(point_goal) >= TARGET_RANGE and step <= TOTAL_STEP:
att_vector = attraction_force(point_current, point_goal)
point_obstacle = closest_point_to_obstacle(point_current, polygon)
# point_obstacle.plot_point()
print('current \npoint obstacle\nattraction\nrepulsive')
point_current.show_value()
point_obstacle.show_value()
# print(point_current.find_distance_between_points(point_obstacle))
if point_current.find_distance_between_points(point_obstacle) <= REPULSIVE_RANGE:
rep_vector = repulsive_force(point_current, point_obstacle, polygon_centroid)
else:
rep_vector = Point(0, 0)
att_vector.show_value()
rep_vector.show_value()
total_vector = total_potential_force(att_vector, rep_vector)
# force_point = po
# point_current.plot_line_between_two_point()
# point_current.show_value()
point_current.add_point(total_vector, STEP_SIZE)
# point_current.show_value()
path.append(Point(point_current.x, point_current.y))
step += 1
return path
# Parameter:
# path contains a sequence of x y coordinate
# Return:
# plot the sequence of dot on a figure
def plot_path(path):
x = []
y = []
for p in path:
# print(p.x, p.y)
x.append(p.x)
y.append(p.y)
plt.plot(x, y, 'k-')
def ik_test(limb, x_new, y_new):
# initialized a node with name
rospy.init_node("rsdk_ik_service_client")
# string variable
ns = "ExternalTools/" + limb + "/PositionKinematicsNode/IKService"
iksvc = rospy.ServiceProxy(ns, SolvePositionIK)
ikreq = SolvePositionIKRequest()
hdr = Header(stamp=rospy.Time.now(), frame_id='base')
poses = {
'left': PoseStamped(
header=hdr,
pose=Pose(
position=Point(
x=0.657579481614,
y=0.851981417433,
z=0.0388352386502,
),
orientation=Quaternion(
x=-0.366894936773,
y=0.885980397775,
z=0.108155782462,
w=0.262162481772,
),
),
),
'right': PoseStamped(
header=hdr,
pose=Pose(
position=Point(
x=x_new
y=y_new,
z=0,
),
orientation=Quaternion(
x=0.7071,
y=0,
z=0.7071,
w=0,
),
),
),
}
ikreq.pose_stamp.append(poses[limb])
try:
rospy.wait_for_service(ns, 5.0)
resp = iksvc(ikreq)
except (rospy.ServiceException, rospy.ROSException), e:
rospy.logerr("Service call failed: %s" % (e,))
return 1
if (resp.isValid[0]):
print("SUCCESS - Valid Joint Solution Found:")
# Format solution into Limb API-compatible dictionary
limb_joints = dict(zip(resp.joints[0].name, resp.joints[0].position))
# print(limb_joints)
else:
print("INVALID POSE - No Valid Joint Solution Found.")
return limb_joints
class Waypoints(object):
def __init__(self, limb, speed, accuracy):
# Create baxter_interface limb instance
self._arm = limb
self._limb = baxter_interface.Limb(self._arm)
# Parameters which will describe joint position moves
self._speed = speed
self._accuracy = accuracy
# Verify robot is enabled
print("Getting robot state... ")
self._rs = baxter_interface.RobotEnable()
self._init_state = self._rs.state().enabled
print("Enabling robot... ")
self._rs.enable()
def play(self, joints_information):
"""
Loops playback of recorded joint position waypoints until program is
exited
"""
rospy.sleep(1.0)
rospy.loginfo("Waypoint Playback Started")
print(" Press Ctrl-C to stop...")
# Set joint position speed ratio for execution
self._limb.set_joint_position_speed(self._speed)
self._limb.move_to_joint_positions(joints_information, timeout=20.0,
threshold=self._accuracy)
self._limb.set_joint_position_speed(0.3)
def clean_shutdown(self):
print("\nExiting example...")
if not self._init_state:
print("Disabling robot...")
self._rs.disable()
return True
def main():
# Baxter Setup
"""RSDK Joint Position Waypoints Example
Records joint positions each time the navigator 'OK/wheel'
button is pressed.
Upon pressing the navigator 'Rethink' button, the recorded joint positions
will begin playing back in a loop.
"""
arg_fmt = argparse.RawDescriptionHelpFormatter
parser = argparse.ArgumentParser(formatter_class=arg_fmt,
description=main.__doc__)
required = parser.add_argument_group('required arguments')
required.add_argument(
'-l', '--limb', required=True, choices=['left', 'right'],
help='limb to record/playback waypoints'
)
parser.add_argument(
'-s', '--speed', default=0.3, type=float,
help='joint position motion speed ratio [0.0-1.0] (default:= 0.3)'
)
parser.add_argument(
'-a', '--accuracy',
default=baxter_interface.settings.JOINT_ANGLE_TOLERANCE, type=float,
help='joint position accuracy (rad) at which waypoints must achieve'
)
args = parser.parse_args(rospy.myargv()[1:])
print("Initializing node... ")
# initialized node
rospy.init_node("rsdk_joint_position_waypoints_%s" % (args.limb,))
p_1 = Point(2, 1)
p_2 = Point(10, 1)
p_3 = Point(10, 10)
p_4 = Point(2, 10)
p_5 = Point(2, 8)
p_6 = Point(6, 6)
p_7 = Point(6, 4)
p_8 = Point(1, 2)
polygon = Polygon()
polygon.add_point(p_1)
polygon.add_point(p_2)
polygon.add_point(p_3)
polygon.add_point(p_4)
polygon.add_point(p_5)
polygon.add_point(p_6)
polygon.add_point(p_7)
polygon.add_point(p_8)
polygon.polygon_plot('r-')
convex_polygon = polygon.concave_convex_conversion()
convex_polygon.polygon_plot('g-')
safe_range_polygon = convex_polygon.repulsive_poly(REPULSIVE_POLY_MULTIPLIER)
safe_range_polygon.polygon_plot('b-')
point_centroid = safe_range_polygon.get_polygon_centroid()
# p = Point(-5, -5)
point_centroid.plot_point()
point_start = Point(-5, 5)
p_obs = closest_point_to_obstacle(point_start, safe_range_polygon)
point_start.plot_point()
p_obs.plot_point()
point_goal = Point(15, 0)
point_goal.plot_point()
path = potential_get_path(safe_range_polygon, point_start, point_goal, point_centroid)
# plot_path(path)
# plt.show()
move = Waypoints(args.limb, args.speed, args.accuracy)
# Register clean shutdown
rospy.on_shutdown(move.clean_shutdown())
for p in path:
x = p.x
y = p.y
joints = ik_test(args.limb, x, y)
move.play(joints)
if __name__ == '__main__':
main()