Skip to content

Commit b5597b7

Browse files
committed
Merge branch 'develop'
2 parents 494b321 + 37b65c4 commit b5597b7

File tree

6 files changed

+60
-40
lines changed

6 files changed

+60
-40
lines changed

LICENSE.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
Copyright (c) 2020, Queensland University of Technology (Ben Talbot, David Hall, Haoyang Zhang, Suman Bista, Rohan Smith, Niko Sünderhauf, and Feras Dayoub)
1+
Copyright (c) 2020, Queensland University of Technology (Ben Talbot, David Hall, and Niko Sünderhauf)
22
All rights reserved.
33

44
Redistribution and use in source and binary forms, with or without modification,

nodes/debug_move_to_pose

Lines changed: 16 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22

33
from __future__ import print_function
44

5+
import benchbot_spatial as sp
56
import numpy as np
67
import os
78
import rospy
@@ -17,11 +18,6 @@ sys.path.append(
1718
import robot_callbacks as rc
1819

1920

20-
def __SE2_to_SE3(pose):
21-
return np.matmul(rc.__SE3_from_translation(pose[0, 2], pose[1, 2]),
22-
rc.__SE3_from_yaw(rc.__yaw_from_SE2(pose)))
23-
24-
2521
class DummyController():
2622

2723
class DummyEvent():
@@ -70,22 +66,28 @@ if __name__ == '__main__':
7066

7167
# Wait for tf to exist (there's something really dodgy going on here...)
7268
t = None
69+
print("Waiting for tf...")
7370
while not rospy.is_shutdown() and t is None:
7471
try:
7572
t = d.tf_buffer.lookup_transform('map', 'base_link',
7673
rospy.Time.now(),
7774
rospy.Duration(1.0))
7875
except Exception as e:
76+
print("ERROR: %s" % e)
7977
pass
78+
print("Got initial tf.")
8079

8180
while not rospy.is_shutdown():
82-
c = rc.__SE3_to_SE2(rc._current_pose(d))
81+
c = sp.SE3_to_SE2(rc._current_pose(d))
8382

8483
# Get goal from terminal
8584
goal_xyt = None
8685
while goal_xyt is None:
8786
print("Relative goal (format: x,y,th): ", end='')
88-
g = raw_input().split(',')
87+
r = raw_input()
88+
if len(r) == 0:
89+
sys.exit(0)
90+
g = r.split(',')
8991
if len(g) == 3:
9092
goal_xyt = []
9193
for x in g:
@@ -94,19 +96,19 @@ if __name__ == '__main__':
9496
except:
9597
goal_xyt = None
9698
break
97-
goal_rel = rc.__SE3_to_SE2(
98-
np.matmul(rc.__SE3_from_translation(goal_xyt[0], goal_xyt[1]),
99-
rc.__SE3_from_yaw(goal_xyt[2])))
99+
goal_rel = sp.SE3_to_SE2(
100+
np.matmul(sp.SE3_from_translation(goal_xyt[0], goal_xyt[1]),
101+
sp.SE3_from_yaw(goal_xyt[2])))
100102
goal_abs = np.matmul(c, goal_rel)
101103

102104
# Print some information about the goal
103-
ct = rc.__SE2_to_xyt(c)
104-
grt = rc.__SE2_to_xyt(goal_rel)
105-
gat = rc.__SE2_to_xyt(goal_abs)
105+
ct = sp.SE2_to_xyt(c)
106+
grt = sp.SE2_to_xyt(goal_rel)
107+
gat = sp.SE2_to_xyt(goal_abs)
106108
print(
107109
"Going from:\t(%f,%f,%f)\n\tto\t(%f,%f,%f)\n\tdelta\t(%f,%f,%f)" %
108110
(ct[0], ct[1], ct[2], gat[0], gat[1], gat[2], grt[0], grt[1],
109111
grt[2]))
110112

111113
# Try and move to the goal
112-
rc._move_to_pose(__SE2_to_SE3(goal_abs), p, d)
114+
rc._move_to_pose(sp.SE2_to_SE3(goal_abs), p, d)

nodes/noisify_odom

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,7 @@ class PoseNoisifier(object):
107107
o.child_frame_id = self.out_frame_robot
108108
o.pose.pose = _SE3_to_pose_msg(noisy_odom)
109109
o.pose.covariance = odom_msg.pose.covariance
110-
o.twist = self._last_vel
110+
o.twist.twist = self._last_vel
111111
self._pub_odom.publish(o)
112112

113113
t = TransformStamped()

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package format="2">
33
<name>benchbot_robot_controller</name>
4-
<version>2.2.1</version>
4+
<version>2.4.0</version>
55
<description>The benchbot_robot_controller package</description>
66

77
<maintainer email="[email protected]">Ben Talbot</maintainer>

src/benchbot_spatial.py

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,11 @@ def rpy_from_SE3(pose):
2929
return t3.euler.mat2euler(pose[0:3, 0:3])
3030

3131

32+
def SE2_to_SE3(pose):
33+
return np.matmul(SE3_from_translation(pose[0, 2], pose[1, 2]),
34+
SE3_from_yaw(yaw_from_SE2(pose)))
35+
36+
3237
def SE2_to_xyt(pose):
3338
return np.array([pose[0, 2], pose[1, 2], yaw_from_SE2(pose)])
3439

src/robot_callbacks.py

Lines changed: 36 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
import ros_numpy
44
import rospy
55
from geometry_msgs.msg import Twist
6+
from time import time
67

78
_DEFAULT_SPEED_FACTOR = 1
89

@@ -13,12 +14,14 @@
1314

1415
_MOVE_ANGLE_K = 3
1516

16-
_MOVE_POSE_K_RHO = 1
17-
_MOVE_POSE_K_ALPHA = 4
18-
_MOVE_POSE_K_BETA = -1.5
17+
_MOVE_TIMEOUT = 30
1918

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
2225

2326

2427
def __safe_dict_get(d, key, default):
@@ -79,7 +82,8 @@ def _move_to_angle(goal, publisher, controller):
7982
gamma = None
8083
vel_msg = Twist()
8184
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
8387
not controller.instance.is_collided() and
8488
(gamma is None or np.abs(gamma) > _MOVE_TOL_YAW)):
8589
# Get latest orientation error
@@ -106,9 +110,11 @@ def _move_to_pose(goal, publisher, controller):
106110
g = sp.SE3_to_SE2(goal)
107111

108112
rho = None
113+
backwards = None
109114
vel_msg = Twist()
110115
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
112118
not controller.instance.is_collided() and
113119
(rho is None or rho > _MOVE_TOL_DIST)):
114120
# Get latest position error
@@ -118,11 +124,13 @@ def _move_to_pose(goal, publisher, controller):
118124
# Calculate values used in the controller
119125
rho = np.linalg.norm(error[0:2, 2])
120126
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))
122129

123130
# 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)
126134
if backwards:
127135
vel_msg.linear.x = -1 * _MOVE_POSE_K_RHO * rho
128136
vel_msg.angular.z = (
@@ -137,20 +145,25 @@ def _move_to_pose(goal, publisher, controller):
137145
vel_msg.linear.x = _move_speed_factor(controller) * vel_msg.linear.x
138146
vel_msg.angular.z = _move_speed_factor(controller) * vel_msg.angular.z
139147

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
148160

149161
# Publish velocity (don't move if we're already there!)
150162
if (rho > _MOVE_TOL_DIST):
151163
publisher.publish(vel_msg)
152164
hz_rate.sleep()
153-
_move_to_angle(goal, publisher, controller)
165+
if (time() - t < _MOVE_TIMEOUT):
166+
_move_to_angle(goal, publisher, controller)
154167
publisher.publish(Twist())
155168

156169

@@ -240,10 +253,10 @@ def move_angle(data, publisher, controller):
240253
def move_distance(data, publisher, controller):
241254
# Derive a corresponding goal pose & send the robot there
242255
_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)
247260

248261

249262
def move_next(data, publisher, controller):

0 commit comments

Comments
 (0)