3
3
import ros_numpy
4
4
import rospy
5
5
from geometry_msgs .msg import Twist
6
+ from time import time
6
7
7
8
_DEFAULT_SPEED_FACTOR = 1
8
9
13
14
14
15
_MOVE_ANGLE_K = 3
15
16
16
- _MOVE_POSE_K_RHO = 1
17
- _MOVE_POSE_K_ALPHA = 4
18
- _MOVE_POSE_K_BETA = - 1.5
17
+ _MOVE_TIMEOUT = 30
19
18
20
- _MOVE_LINEAR_LIMITS = [- 0.6 , 2.0 ]
21
- _MOVE_ANGULAR_LIMIT = 0.5
19
+ _MOVE_POSE_K_RHO = 2
20
+ _MOVE_POSE_K_ALPHA = 10
21
+ _MOVE_POSE_K_BETA = - 4
22
+
23
+ _MOVE_LINEAR_LIMITS = [- 0.6 , 1.5 ]
24
+ _MOVE_ANGULAR_LIMIT = 1.0
22
25
23
26
24
27
def __safe_dict_get (d , key , default ):
@@ -79,7 +82,8 @@ def _move_to_angle(goal, publisher, controller):
79
82
gamma = None
80
83
vel_msg = Twist ()
81
84
hz_rate = rospy .Rate (_MOVE_HZ )
82
- while (not controller .evt .is_set () and
85
+ t = time ()
86
+ while (time () - t < _MOVE_TIMEOUT and not controller .evt .is_set () and
83
87
not controller .instance .is_collided () and
84
88
(gamma is None or np .abs (gamma ) > _MOVE_TOL_YAW )):
85
89
# Get latest orientation error
@@ -106,9 +110,11 @@ def _move_to_pose(goal, publisher, controller):
106
110
g = sp .SE3_to_SE2 (goal )
107
111
108
112
rho = None
113
+ backwards = None
109
114
vel_msg = Twist ()
110
115
hz_rate = rospy .Rate (_MOVE_HZ )
111
- while (not controller .evt .is_set () and
116
+ t = time ()
117
+ while (time () - t < _MOVE_TIMEOUT and not controller .evt .is_set () and
112
118
not controller .instance .is_collided () and
113
119
(rho is None or rho > _MOVE_TOL_DIST )):
114
120
# Get latest position error
@@ -118,11 +124,13 @@ def _move_to_pose(goal, publisher, controller):
118
124
# Calculate values used in the controller
119
125
rho = np .linalg .norm (error [0 :2 , 2 ])
120
126
alpha = np .arctan2 (error [1 , 2 ], error [0 , 2 ])
121
- beta = sp .pi_wrap (- sp .yaw_from_SE2 (current ) - alpha + sp .yaw_from_SE2 (g ))
127
+ beta = sp .pi_wrap (- sp .yaw_from_SE2 (current ) - alpha +
128
+ sp .yaw_from_SE2 (g ))
122
129
123
130
# Construct velocity message
124
- backwards = (rho > _MOVE_TOL_DIST and
125
- np .abs (np .arctan2 (error [1 , 2 ], error [0 , 2 ])) > np .pi / 2 )
131
+ if backwards is None :
132
+ backwards = (np .abs (np .arctan2 (error [1 , 2 ], error [0 , 2 ])) >
133
+ 1.05 * np .pi / 2 )
126
134
if backwards :
127
135
vel_msg .linear .x = - 1 * _MOVE_POSE_K_RHO * rho
128
136
vel_msg .angular .z = (
@@ -137,20 +145,25 @@ def _move_to_pose(goal, publisher, controller):
137
145
vel_msg .linear .x = _move_speed_factor (controller ) * vel_msg .linear .x
138
146
vel_msg .angular .z = _move_speed_factor (controller ) * vel_msg .angular .z
139
147
140
- vel_msg .linear .x = (
141
- _MOVE_LINEAR_LIMITS [1 ] if vel_msg .linear .x > _MOVE_LINEAR_LIMITS [1 ]
142
- else _MOVE_LINEAR_LIMITS [0 ]
143
- if vel_msg .linear .x < _MOVE_LINEAR_LIMITS [0 ] else vel_msg .linear .x )
144
- vel_msg .angular .z = (
145
- _MOVE_ANGULAR_LIMIT if vel_msg .angular .z > _MOVE_ANGULAR_LIMIT else
146
- - _MOVE_ANGULAR_LIMIT
147
- if vel_msg .angular .z < - _MOVE_ANGULAR_LIMIT else vel_msg .angular .z )
148
+ clamped_l = min (_MOVE_LINEAR_LIMITS [1 ],
149
+ max (_MOVE_LINEAR_LIMITS [0 ], vel_msg .linear .x ))
150
+ clamped_a = min (_MOVE_ANGULAR_LIMIT ,
151
+ max (- _MOVE_ANGULAR_LIMIT , vel_msg .angular .z ))
152
+ factor = max (abs (vel_msg .linear .x / clamped_l ),
153
+ abs (vel_msg .angular .z / clamped_a ))
154
+ # print(
155
+ # "r,a,p: (%f,%f,%f) B:%d l,a: (%f, %f) lc,ac: (%f, %f)" %
156
+ # (rho, alpha, beta, backwards, vel_msg.linear.x, vel_msg.angular.z,
157
+ # vel_msg.linear.x / factor, vel_msg.angular.z / factor))
158
+ vel_msg .linear .x = vel_msg .linear .x / factor
159
+ vel_msg .angular .z = vel_msg .angular .z / factor
148
160
149
161
# Publish velocity (don't move if we're already there!)
150
162
if (rho > _MOVE_TOL_DIST ):
151
163
publisher .publish (vel_msg )
152
164
hz_rate .sleep ()
153
- _move_to_angle (goal , publisher , controller )
165
+ if (time () - t < _MOVE_TIMEOUT ):
166
+ _move_to_angle (goal , publisher , controller )
154
167
publisher .publish (Twist ())
155
168
156
169
@@ -240,10 +253,10 @@ def move_angle(data, publisher, controller):
240
253
def move_distance (data , publisher , controller ):
241
254
# Derive a corresponding goal pose & send the robot there
242
255
_move_to_pose (
243
- np .matmul (_current_pose ( controller ),
244
- sp . SE3_from_translation ( __safe_dict_get ( data , 'distance' ,
245
- 0 ))), publisher ,
246
- controller )
256
+ np .matmul (
257
+ _current_pose ( controller ) ,
258
+ sp . SE3_from_translation ( __safe_dict_get ( data , 'distance' , 0 ))),
259
+ publisher , controller )
247
260
248
261
249
262
def move_next (data , publisher , controller ):
0 commit comments