add camera unit test
This commit is contained in:
@@ -28,7 +28,7 @@ class CameraController(Node):
|
||||
|
||||
self.get_logger().info("Camera controller started. Waiting for service call...")
|
||||
self.srv = self.create_service(
|
||||
TakePicture, 'drone/picture', self.take_picture_callback)
|
||||
TakePicture, '/drone/picture', self.take_picture_callback)
|
||||
|
||||
self.websocket = None
|
||||
self.server = None
|
||||
|
||||
@@ -11,9 +11,6 @@
|
||||
<exec_depend>drone_services</exec_depend>
|
||||
<exec_depend>sensor_msgs</exec_depend>
|
||||
|
||||
<test_depend>ament_copyright</test_depend>
|
||||
<test_depend>ament_flake8</test_depend>
|
||||
<test_depend>ament_pep257</test_depend>
|
||||
<test_depend>python3-pytest</test_depend>
|
||||
|
||||
<export>
|
||||
|
||||
72
src/camera/test/test_camera.py
Normal file
72
src/camera/test/test_camera.py
Normal file
@@ -0,0 +1,72 @@
|
||||
import os
|
||||
import sys
|
||||
import unittest
|
||||
import time
|
||||
|
||||
import launch
|
||||
import launch_ros
|
||||
import launch_ros.actions
|
||||
import launch_testing.actions
|
||||
import pytest
|
||||
import rclpy
|
||||
|
||||
from drone_services.srv import TakePicture
|
||||
|
||||
@pytest.mark.rostest
|
||||
def generate_test_description():
|
||||
file_path = os.path.dirname(__file__)
|
||||
camera_node = launch_ros.actions.Node(
|
||||
executable=sys.executable,
|
||||
arguments=[os.path.join(file_path, '..', 'camera', 'camera.py')],
|
||||
additional_env={'PYTHONUNBUFFERED': '1'}
|
||||
)
|
||||
|
||||
return (
|
||||
launch.LaunchDescription([
|
||||
camera_node,
|
||||
launch_testing.actions.ReadyToTest(),
|
||||
]),
|
||||
{
|
||||
'camera_node': camera_node,
|
||||
}
|
||||
)
|
||||
|
||||
class CameraUnitTest(unittest.TestCase):
|
||||
|
||||
@classmethod
|
||||
def setUpClass(cls):
|
||||
rclpy.init()
|
||||
|
||||
@classmethod
|
||||
def tearDownClass(cls):
|
||||
rclpy.shutdown()
|
||||
|
||||
def setUp(self):
|
||||
self.node = rclpy.create_node('test_camera')
|
||||
self.service_called = False
|
||||
|
||||
def tearDown(self):
|
||||
self.node.destroy_node()
|
||||
|
||||
def service_call_callback(self,future):
|
||||
self.assertIsNotNone(future.result())
|
||||
self.assertEqual(future.result().filename, "/home/ubuntu/test_image.jpg")
|
||||
self.assertTrue(os.path.exists("/home/ubuntu/test_image.jpg"))
|
||||
self.service_called = True
|
||||
|
||||
def test_camera_save_image(self,camera_node,proc_output):
|
||||
# call camera service
|
||||
camera_client = self.node.create_client(TakePicture, '/drone/take_picture')
|
||||
while not camera_client.wait_for_service(timeout_sec=1.0):
|
||||
self.node.get_logger().info('camera service not available, waiting again...')
|
||||
request = TakePicture.Request()
|
||||
request.input_name = "/home/ubuntu/test_image.jpg"
|
||||
try:
|
||||
while True:
|
||||
rclpy.spin_once(self.node,timeout_sec=0.1)
|
||||
if not self.service_called:
|
||||
camera_client.call_async(request).add_done_callback(self.service_call_callback)
|
||||
else:
|
||||
break
|
||||
finally:
|
||||
self.node.destroy_client(camera_client)
|
||||
@@ -1,23 +0,0 @@
|
||||
# Copyright 2015 Open Source Robotics Foundation, Inc.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
from ament_copyright.main import main
|
||||
import pytest
|
||||
|
||||
|
||||
@pytest.mark.copyright
|
||||
@pytest.mark.linter
|
||||
def test_copyright():
|
||||
rc = main(argv=['.', 'test'])
|
||||
assert rc == 0, 'Found errors'
|
||||
@@ -1,25 +0,0 @@
|
||||
# Copyright 2017 Open Source Robotics Foundation, Inc.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
from ament_flake8.main import main_with_errors
|
||||
import pytest
|
||||
|
||||
|
||||
@pytest.mark.flake8
|
||||
@pytest.mark.linter
|
||||
def test_flake8():
|
||||
rc, errors = main_with_errors(argv=[])
|
||||
assert rc == 0, \
|
||||
'Found %d code style errors / warnings:\n' % len(errors) + \
|
||||
'\n'.join(errors)
|
||||
@@ -1,23 +0,0 @@
|
||||
# Copyright 2015 Open Source Robotics Foundation, Inc.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
from ament_pep257.main import main
|
||||
import pytest
|
||||
|
||||
|
||||
@pytest.mark.linter
|
||||
@pytest.mark.pep257
|
||||
def test_pep257():
|
||||
rc = main(argv=['.', 'test'])
|
||||
assert rc == 0, 'Found code style errors / warnings'
|
||||
@@ -8,10 +8,6 @@
|
||||
<license>Apache License 2.0</license>
|
||||
<depend>rclpy</depend>
|
||||
<depend>drone_services</depend>
|
||||
|
||||
<test_depend>ament_copyright</test_depend>
|
||||
<test_depend>ament_flake8</test_depend>
|
||||
<test_depend>ament_pep257</test_depend>
|
||||
<test_depend>python3-pytest</test_depend>
|
||||
|
||||
<export>
|
||||
|
||||
Reference in New Issue
Block a user