diff --git a/builder/image-ros.sh b/builder/image-ros.sh index 02dfdecc6..04d58b959 100755 --- a/builder/image-ros.sh +++ b/builder/image-ros.sh @@ -140,7 +140,8 @@ my_travis_retry apt-get install -y --no-install-recommends \ ros-${ROS_DISTRO}-cmake-modules \ ros-${ROS_DISTRO}-image-view \ ros-${ROS_DISTRO}-nodelet-topic-tools \ - ros-${ROS_DISTRO}-stereo-msgs + ros-${ROS_DISTRO}-stereo-msgs \ + ros-${ROS_DISTRO}-vision-msgs # TODO move GeographicLib datasets to Mavros debian package echo_stamp "Install GeographicLib datasets (needed for mavros)" \ diff --git a/builder/test/tests.py b/builder/test/tests.py index 2af206016..48da14510 100755 --- a/builder/test/tests.py +++ b/builder/test/tests.py @@ -6,6 +6,9 @@ import rospy from geometry_msgs.msg import PoseStamped from sensor_msgs.msg import Range, BatteryState +from vision_msgs.msg import BoundingBox2D, BoundingBox2DArray, BoundingBox3D, BoundingBox3DArray, \ + Classification2D, Classification3D, Detection2D, Detection2DArray, Detection3D, Detection3DArray, \ + ObjectHypothesis, ObjectHypothesisWithPose, VisionInfo import cv2 import cv2.aruco diff --git a/builder/test/tests.sh b/builder/test/tests.sh index 16853f65f..22c1f5fb5 100755 --- a/builder/test/tests.sh +++ b/builder/test/tests.sh @@ -61,6 +61,7 @@ rosversion web_video_server rosversion nodelet rosversion image_view rosversion stereo_msgs +rosversion vision_msgs [[ $(rosversion ws281x) == "0.0.13" ]]