diff --git a/package.xml b/package.xml
index 4b631cc..3a1f590 100644
--- a/package.xml
+++ b/package.xml
@@ -29,9 +29,10 @@
angles
boost
eigen
+ python-numpy
roscpp
sensor_msgs
tf
- unittest
+ rosunit
diff --git a/test/projection_test.py b/test/projection_test.py
index a6102c0..e9da60c 100755
--- a/test/projection_test.py
+++ b/test/projection_test.py
@@ -26,7 +26,7 @@ def build_constant_scan(
raise BuildScanException
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.angle_min = angle_min
scan.angle_max = angle_max
@@ -42,13 +42,6 @@ def build_constant_scan(
class ProjectionTest(unittest.TestCase):
- @classmethod
- def setUpClass(cls):
- rospy.init_node('projection_test')
-
- def tearDown(self):
- pass
-
def test_project_laser(self):
tolerance = 6 # decimal places
projector = LaserProjection()