Skip to content

Commit 63d4096

Browse files
Merge pull request #43 from nobleo/refactor/tf2-migration
Refactor/tf2 migration
2 parents 6ee5df9 + 6f21300 commit 63d4096

File tree

3 files changed

+12
-14
lines changed

3 files changed

+12
-14
lines changed

nodes/coverage_progress

Lines changed: 10 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
#! /usr/bin/env python
22

33
import rospy
4-
import tf
4+
import tf2_ros
55
from nav_msgs.msg import OccupancyGrid
66
from numpy import ones, sum
77
from std_msgs.msg import Float32, Header
@@ -27,10 +27,9 @@ class CoverageProgressNode(object):
2727
DIRTY = 100
2828

2929
def __init__(self):
30-
self.listener = tf.TransformListener()
30+
self.tf_buffer = tf2_ros.Buffer()
31+
self.listener = tf2_ros.TransformListener(self.tf_buffer)
3132

32-
x = None # type: float
33-
y = None # type: float
3433
self._coverage_area = None # type: Tuple[float, float]
3534

3635
self.coverage_resolution = None # type: float # How big is a cell [m]
@@ -49,7 +48,7 @@ class CoverageProgressNode(object):
4948
self.reset_srv = rospy.Service('reset', Trigger, self.reset)
5049

5150
self._rate = rospy.get_param("~rate", 10.0)
52-
self._update_timer = rospy.Timer(rospy.Duration(1.0/self._rate), self._update_callback)
51+
self._update_timer = rospy.Timer(rospy.Duration(1.0/self._rate), self._update_callback, reset=True)
5352

5453
def _initialize_map(self):
5554
# Initialize coverage matrix
@@ -98,17 +97,19 @@ class CoverageProgressNode(object):
9897
# Get the position of point (0,0,0) the coverage_disk frame wrt. the map frame (which can both be remapped if need be)
9998

10099
try:
101-
(coveragepos, rot) = self.listener.lookupTransform(self.map_frame, self.coverage_frame, rospy.Time(0))
102-
except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
100+
coverage_tf = self.tf_buffer.lookup_transform(self.map_frame, self.coverage_frame, rospy.Time(0))
101+
except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException) as e:
102+
rospy.logwarn(e)
103103
return
104104

105105
# Element of matrix corresponding to middle of coverage surface
106-
x_point = int((coveragepos[X] - self.grid.info.origin.position.x) / self.coverage_resolution)
107-
y_point = int((coveragepos[Y] - self.grid.info.origin.position.y) / self.coverage_resolution)
106+
x_point = int((coverage_tf.transform.translation.x - self.grid.info.origin.position.x) / self.coverage_resolution)
107+
y_point = int((coverage_tf.transform.translation.y - self.grid.info.origin.position.y) / self.coverage_resolution)
108108

109109
# Initialize message
110110
self.grid.header = Header()
111111
self.grid.header.frame_id = self.map_frame
112+
self.grid.header.stamp = coverage_tf.header.stamp
112113

113114
# Loop over amount of cells covered in x (j) and y (i) direction
114115
for i in range(2 * self.coverage_radius_cells):
@@ -126,9 +127,6 @@ class CoverageProgressNode(object):
126127

127128
if cell_in_coverage_circle and cell_in_grid:
128129
self.grid.data[array_index] = max(0, self.grid.data[array_index] - self.coverage_effectivity)
129-
else:
130-
rospy.logdebug("x_point %i y_point %i, x_meas %f, y_meas %f", x_point, y_point, coveragepos[X],
131-
coveragepos[Y])
132130

133131
coverage_progress = float(sum([self.grid.data < self.DIRTY])) / (self.grid.info.width * self.grid.info.height)
134132

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222
<depend>pluginlib</depend>
2323
<depend>nav_core</depend>
2424
<depend>roscpp</depend>
25-
<depend>tf</depend>
25+
<depend>tf2_ros</depend>
2626
<exec_depend>amcl</exec_depend>
2727
<exec_depend>joint_state_publisher</exec_depend>
2828
<exec_depend>map_server</exec_depend>

test/full_coverage_path_planner/test_full_coverage_path_planner.launch

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@
7474
<param name="~target_area/y" value="$(arg coverage_area_size_y)" />
7575
<param name="~coverage_radius" value="$(arg tool_radius)" />
7676
<remap from="reset" to="coverage_progress/reset" />
77-
<param name="~map_frame" value="/coverage_map"/>
77+
<param name="~map_frame" value="coverage_map"/>
7878
</node>
7979

8080
<!-- Trigger planner by publishing a move_base goal -->

0 commit comments

Comments
 (0)