-
Notifications
You must be signed in to change notification settings - Fork 1
/
trajectory.py
205 lines (159 loc) · 6.74 KB
/
trajectory.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
#! /usr/bin/python3
import math
import numpy
import sys
import termios
from geometry_msgs.msg import Twist
from rclpy.node import Node
from rclpy.qos import QoSProfile
from nav_msgs.msg import Odometry
import rclpy
terminal_msg = ""
class Turtlebot3Path():
def turn(angle, angular_velocity, step):
twist = Twist()
if math.fabs(angle) > 0.01: # 0.01 is small enough value
if angle >= math.pi:
twist.angular.z = -angular_velocity
elif math.pi > angle and angle >= 0:
twist.angular.z = angular_velocity
elif 0 > angle and angle >= -math.pi:
twist.angular.z = -angular_velocity
elif angle > -math.pi:
twist.angular.z = angular_velocity
else:
step += 1
return twist, step
def go_straight(distance, linear_velocity, step):
twist = Twist()
if distance > 0.01: # 0.01 is small enough value
twist.linear.x = linear_velocity
else:
step += 1
return twist, step
class Turtlebot3PositionControl(Node):
def __init__(self):
super().__init__('turtlebot3_position_control')
"""************************************************************
** Initialise variables
************************************************************"""
self.odom = Odometry()
self.last_pose_x = 0.0
self.last_pose_y = 0.0
self.last_pose_theta = 0.0
self.goal_pose_x = 0.0
self.goal_pose_y = 0.0
self.goal_pose_theta = 0.0
self.step = 1
self.get_key_state = False
self.init_odom_state = False # To get the initial pose at the beginning
"""************************************************************
** Initialise ROS publishers and subscribers
************************************************************"""
qos = QoSProfile(depth=10)
# Initialise publishers
self.cmd_vel_pub = self.create_publisher(Twist, 'cmd_vel', qos)
self.original_odom = self.create_publisher(Odometry, 'ori_odom', qos)
# Initialise subscribers
self.odom_sub = self.create_subscription(
Odometry,
'odom',
self.odom_callback,
qos)
"""************************************************************
** Initialise timers
************************************************************"""
self.update_timer = self.create_timer(0.010, self.update_callback) # unit: s
self.get_logger().info("Turtlebot3 position control node has been initialised.")
"""*******************************************************************************
** Callback functions and relevant functions
*******************************************************************************"""
def odom_callback(self, msg):
self.original_odom.publish(msg)
self.last_pose_x = msg.pose.pose.position.x
self.last_pose_y = msg.pose.pose.position.y
_, _, self.last_pose_theta = self.euler_from_quaternion(msg.pose.pose.orientation)
self.init_odom_state = True
def update_callback(self):
if self.init_odom_state is True:
self.generate_path()
def generate_path(self):
twist = Twist()
if self.get_key_state is False:
input_x, input_y, input_theta = self.get_key()
self.goal_pose_x = self.last_pose_x + input_x
self.goal_pose_y = self.last_pose_y + input_y
self.goal_pose_theta = self.last_pose_theta + input_theta
self.get_key_state = True
else:
# Step 1: Turn
if self.step == 1:
path_theta = math.atan2(
self.goal_pose_y - self.last_pose_y,
self.goal_pose_x - self.last_pose_x)
angle = path_theta - self.last_pose_theta
angular_velocity = 0.1 # unit: rad/s
twist, self.step = Turtlebot3Path.turn(angle, angular_velocity, self.step)
# Step 2: Go Straight
elif self.step == 2:
distance = math.sqrt(
(self.goal_pose_x - self.last_pose_x)**2 +
(self.goal_pose_y - self.last_pose_y)**2)
linear_velocity = 0.1 # unit: m/s
twist, self.step = Turtlebot3Path.go_straight(distance, linear_velocity, self.step)
# Step 3: Turn
elif self.step == 3:
angle = self.goal_pose_theta - self.last_pose_theta
angular_velocity = 0.1 # unit: rad/s
twist, self.step = Turtlebot3Path.turn(angle, angular_velocity, self.step)
# Reset
elif self.step == 4:
self.step = 1
self.get_key_state = False
self.cmd_vel_pub.publish(twist)
def get_key(self):
# Print terminal message and get inputs
# print(terminal_msg)
# input_x = float(input("Input x: "))
# input_y = float(input("Input y: "))
# input_theta = float(input("Input theta: "))
input_x = 1.1
input_y = 1.1
input_theta = 30
print(f'{input_x=} {input_y=} {input_theta=}')
while input_theta > 180 or input_theta < -180:
self.get_logger().info("Enter a value for theta between -180 and 180")
input_theta = input("Input theta: ")
input_theta = numpy.deg2rad(input_theta) # Convert [deg] to [rad]
settings = termios.tcgetattr(sys.stdin)
termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
return input_x, input_y, input_theta
"""*******************************************************************************
** Below should be replaced when porting for ROS 2 Python tf_conversions is done.
*******************************************************************************"""
def euler_from_quaternion(self, quat):
"""
Convert quaternion (w in last place) to euler roll, pitch, yaw.
quat = [x, y, z, w]
"""
x = quat.x
y = quat.y
z = quat.z
w = quat.w
sinr_cosp = 2 * (w * x + y * z)
cosr_cosp = 1 - 2 * (x * x + y * y)
roll = numpy.arctan2(sinr_cosp, cosr_cosp)
sinp = 2 * (w * y - z * x)
pitch = numpy.arcsin(sinp)
siny_cosp = 2 * (w * z + x * y)
cosy_cosp = 1 - 2 * (y * y + z * z)
yaw = numpy.arctan2(siny_cosp, cosy_cosp)
return roll, pitch, yaw
def main(args=None):
rclpy.init(args=args)
turtlebot3_position_control = Turtlebot3PositionControl()
rclpy.spin(turtlebot3_position_control)
turtlebot3_position_control.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()