get test to run as rosunit

This commit is contained in:
Vincent Rabaud 2014-06-08 15:00:57 +02:00
parent 5d497a9295
commit cba03f270e
2 changed files with 3 additions and 9 deletions

View File

@ -29,9 +29,10 @@
<run_depend>angles</run_depend> <run_depend>angles</run_depend>
<run_depend>boost</run_depend> <run_depend>boost</run_depend>
<run_depend>eigen</run_depend> <run_depend>eigen</run_depend>
<run_depend>python-numpy</run_depend>
<run_depend>roscpp</run_depend> <run_depend>roscpp</run_depend>
<run_depend>sensor_msgs</run_depend> <run_depend>sensor_msgs</run_depend>
<run_depend>tf</run_depend> <run_depend>tf</run_depend>
<test_depend>unittest</test_depend> <test_depend>rosunit</test_depend>
</package> </package>

View File

@ -26,7 +26,7 @@ def build_constant_scan(
raise BuildScanException raise BuildScanException
scan = LaserScan() scan = LaserScan()
scan.header.stamp = rospy.Time.now() scan.header.stamp = rospy.rostime.Time.from_sec(10.10)
scan.header.frame_id = "laser_frame" scan.header.frame_id = "laser_frame"
scan.angle_min = angle_min scan.angle_min = angle_min
scan.angle_max = angle_max scan.angle_max = angle_max
@ -42,13 +42,6 @@ def build_constant_scan(
class ProjectionTest(unittest.TestCase): class ProjectionTest(unittest.TestCase):
@classmethod
def setUpClass(cls):
rospy.init_node('projection_test')
def tearDown(self):
pass
def test_project_laser(self): def test_project_laser(self):
tolerance = 6 # decimal places tolerance = 6 # decimal places
projector = LaserProjection() projector = LaserProjection()