Mentions légales du service

Skip to content
Snippets Groups Projects
Commit 06c40c53 authored by Paolo Rota's avatar Paolo Rota
Browse files

Merge branch 'devel' into 'main'

add soft BioEstimation unit_test

See merge request !2
parents d83e8d84 787f6257
No related branches found
No related tags found
1 merge request!2add soft BioEstimation unit_test
......@@ -21,5 +21,11 @@ include_directories(
catkin_install_python(PROGRAMS
src/soft_biometrics_estimation.py
test/unittest_soft_biometrics_estimation.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
if(CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
add_rostest(test/test_soft_biometrics_estimation.test)
endif()
\ No newline at end of file
......@@ -12,6 +12,8 @@
<build_depend>rospy</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>rostest</build_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>sensor_msgs</build_export_depend>
......
<launch>
<arg name="input_topic" default="/head_front_camera/color/image_raw/compressed/"/>
<node pkg="wp4_soft_biometrics_estimation" type="soft_biometrics_estimation.py" respawn="true" name="soft_biometrics_estimation">
<param name="input_topic" type="string" value="$(arg input_topic)"/>
</node>
<test test-name="test_soft_biometrics_estimation" pkg="wp4_soft_biometrics_estimation" type="unittest_soft_biometrics_estimation.py" />
</launch>
#!/usr/bin/env python3
# -*- coding:utf-8 -*-
import pathlib
import sys
file_path = pathlib.Path(__file__).parent.absolute()
sys.path.append(str(file_path))
sys.path.append(str(file_path.parent.parent))
print(sys.path)
import unittest
# ROS libraries
import roslib
import rospy
from time import sleep
# Ros Messages
from sensor_msgs.msg import CompressedImage
from wp4_msgs.msg import BoxDetectionFrame, SoftBiometrics, SoftBiometricsFrame
class TestSoftBioEstimation(unittest.TestCase):
soft_biometrics_estimation_ok = False
def _callback(self, data):
self.soft_biometrics_estimation_ok = True
def test_if_mask_detection_publish(self):
rospy.Subscriber("/vision_msgs/soft_biometrics", SoftBiometricsFrame, self._callback)
counter = 0
while not rospy.is_shutdown() and counter < 5 and (not self.soft_biometrics_estimation_ok):
sleep(1)
counter += 1
self.assertTrue(self.soft_biometrics_estimation_ok)
if __name__ == "__main__":
import rostest
rospy.init_node("test_soft_bio_estimation", log_level=rospy.INFO)
rostest.rosrun("soft-biometrics-estimation", "unittest_soft_biometrics_estimation", TestSoftBioEstimation)
\ No newline at end of file
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment