Skip to content

Commit ebaefb9

Browse files
Move to pose
1 parent 5154cf4 commit ebaefb9

File tree

1 file changed

+99
-0
lines changed

1 file changed

+99
-0
lines changed
Lines changed: 99 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,99 @@
1+
"""
2+
Move to specified pose
3+
Author: Daniel Ingram (daniel-s-ingram)
4+
5+
P. I. Corke, "Robotics, Vision & Control", Springer 2017, ISBN 978-3-319-54413-7
6+
"""
7+
8+
from __future__ import print_function, division
9+
10+
import matplotlib.pyplot as plt
11+
import numpy as np
12+
13+
from math import cos, sin, sqrt, atan2, pi
14+
from random import random
15+
16+
Kp_rho = 3
17+
Kp_alpha = 5
18+
Kp_beta = -2
19+
dt = 0.01
20+
21+
#Corners of triangular vehicle when pointing to the right (0 radians)
22+
p1_i = np.array([0.5, 0, 1]).T
23+
p2_i = np.array([-0.5, 0.25, 1]).T
24+
p3_i = np.array([-0.5, -0.25, 1]).T
25+
26+
x_traj = []
27+
y_traj = []
28+
29+
plt.ion()
30+
31+
def move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal):
32+
"""
33+
rho is the distance between the robot and the goal position
34+
alpha is the angle to the goal relative to the heading of the robot
35+
beta is the angle between the robot's position and the goal position plus the goal angle
36+
37+
Kp_rho*rho and Kp_alpha*alpha drive the robot along a line towards the goal
38+
Kp*beta*beta rotates the line so that it is parallel to the goal angle
39+
"""
40+
x = x_start
41+
y = y_start
42+
theta = theta_start
43+
while True:
44+
x_diff = x_goal - x
45+
y_diff = y_goal - y
46+
47+
rho = sqrt(x_diff**2 + y_diff**2)
48+
alpha = atan2(y_diff, x_diff) - theta
49+
beta = theta_goal - theta - alpha
50+
51+
v = Kp_rho*rho
52+
w = Kp_alpha*alpha + Kp_beta*beta
53+
54+
if alpha > pi/2 or alpha < -pi/2:
55+
v = -v
56+
57+
theta = theta + w*dt
58+
x = x + v*cos(theta)*dt
59+
y = y + v*sin(theta)*dt
60+
x_traj.append(x)
61+
y_traj.append(y)
62+
63+
plot_vehicle(x, y, theta, x_start, y_start, x_goal, y_goal, x_traj, y_traj)
64+
65+
66+
def plot_vehicle(x, y, theta, x_start, y_start, x_goal, y_goal, x_traj, y_traj):
67+
T = transformation_matrix(x, y, theta)
68+
p1 = np.matmul(T, p1_i)
69+
p2 = np.matmul(T, p2_i)
70+
p3 = np.matmul(T, p3_i)
71+
plt.cla()
72+
plt.plot([p1[0], p2[0]], [p1[1], p2[1]], 'k-')
73+
plt.plot([p2[0], p3[0]], [p2[1], p3[1]], 'k-')
74+
plt.plot([p3[0], p1[0]], [p3[1], p1[1]], 'k-')
75+
plt.plot(x_start, y_start, 'r*')
76+
plt.plot(x_goal, y_goal, 'g*')
77+
plt.plot(x_traj, y_traj, 'b--')
78+
plt.xlim(0, 20)
79+
plt.ylim(0, 20)
80+
plt.show()
81+
plt.pause(dt/10)
82+
83+
def transformation_matrix(x, y, theta):
84+
return np.array([
85+
[cos(theta), -sin(theta), x],
86+
[sin(theta), cos(theta), y],
87+
[0, 0, 1]
88+
])
89+
90+
if __name__ == '__main__':
91+
x_start = 4 #20*random()
92+
y_start = 15 #20*random()
93+
theta_start = pi/2 #2*pi*random() - pi
94+
x_goal = 13 #20*random()
95+
y_goal = 3 #20*random()
96+
theta_goal = -pi/2 #2*pi*random() - pi
97+
print("Initial x: %.2f m\nInitial y: %.2f m\nInitial theta: %.2f rad\n" % (x_start, y_start, theta_start))
98+
print("Goal x: %.2f m\nGoal y: %.2f m\nGoal theta: %.2f rad\n" % (x_goal, y_goal, theta_goal))
99+
move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal)

0 commit comments

Comments
 (0)