Skip to content

Commit 9619494

Browse files
author
Alexander Gutenkunst
committed
Port auto_init_403 test to ROS2
1 parent fe439f0 commit 9619494

File tree

4 files changed

+169
-59
lines changed

4 files changed

+169
-59
lines changed

fiducial_slam/CMakeLists.txt

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -86,12 +86,29 @@ install(FILES fiducials.rviz
8686
###########
8787

8888
if(BUILD_TESTING)
89+
8990
find_package(ament_cmake_gtest REQUIRED)
91+
find_package(ros_testing REQUIRED)
92+
93+
install(DIRECTORY test/test_images
94+
DESTINATION share/${PROJECT_NAME}/test
95+
)
96+
97+
# transform_var_test
9098
ament_add_gtest(transform_var_test
9199
test/transform_var_test.cpp
92100
src/transform_with_variance.cpp)
93101
ament_target_dependencies(transform_var_test
94102
"geometry_msgs")
103+
104+
# auto_init_403_test
105+
ament_add_gtest_executable(
106+
auto_init_403_test
107+
test/auto_init_403_test.cpp
108+
)
109+
target_link_libraries(auto_init_403_test)
110+
ament_target_dependencies(auto_init_403_test ${DEPENDENCIES})
111+
add_ros_test(test/auto_init_403.test.py ARGS "test_binary_dir:=${CMAKE_CURRENT_BINARY_DIR}")
95112
endif()
96113
# if(CATKIN_ENABLE_TESTING)
97114
# find_package(catkin REQUIRED COMPONENTS

fiducial_slam/package.xml

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,9 @@
2727
<exec_depend>rosidl_default_runtime</exec_depend>
2828

2929
<test_depend>ament_lint_common</test_depend>
30+
31+
<test_depend>ros_testing</test_depend>
32+
<test_depend>ament_cmake_test</test_depend>
3033
<member_of_group>rosidl_interface_packages</member_of_group>
3134
<export>
3235
<build_type>ament_cmake</build_type>
Lines changed: 83 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,83 @@
1+
import unittest
2+
3+
import launch
4+
import launch_ros
5+
import launch_testing
6+
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
7+
from ament_index_python.packages import get_package_share_directory
8+
9+
import pytest
10+
11+
@pytest.mark.rostest
12+
def generate_test_description():
13+
test_node = launch_ros.actions.Node(
14+
executable=PathJoinSubstitution([LaunchConfiguration('test_binary_dir'), 'auto_init_403_test']),
15+
parameters=[
16+
{"image_directory":get_package_share_directory('fiducial_slam') + '/test/test_images/'}
17+
],
18+
output='screen',
19+
)
20+
21+
static_tranform_publisher = launch_ros.actions.Node(
22+
package='tf2_ros',
23+
executable='static_transform_publisher',
24+
name='camera_base',
25+
arguments="0.035 0.145 0.14 -1.479119 -0.041544 -1.204205 base_link camera".split()
26+
)
27+
28+
aruco_detect = launch_ros.actions.Node(
29+
package='aruco_detect',
30+
namespace='aruco_detect',
31+
executable='aruco_detect',
32+
name='aruco_detect',
33+
parameters=[
34+
{"image_transport":'raw'},
35+
{"publish_images":True},
36+
{"fiducial_len":0.145},
37+
],
38+
#Not sure if the remapping is working properly TODO
39+
remappings=[
40+
('camera/compressed', 'camera/image/compressed'),
41+
('fiducial_vertices', '/fiducial_vertices'),
42+
('fiducial_transforms', '/fiducial_transforms')
43+
]
44+
)
45+
46+
fiducial_slam = launch_ros.actions.Node(
47+
package='fiducial_slam',
48+
executable='fiducial_slam_node',
49+
name='fiducial_slam_node',
50+
parameters=[
51+
{"map_frame":'map'},
52+
{"odom_frame":""},
53+
{"base_frame":"base_link"},
54+
{"future_date_transforms", "0.0"},
55+
{"publish_6dof_pose","true"},
56+
{"map_file":"/dev/null"}
57+
],
58+
)
59+
60+
61+
return launch.LaunchDescription([
62+
launch.actions.DeclareLaunchArgument(name='test_binary_dir', # From https://github.com/ros-planning/moveit2/blob/1e1337b46daed0aaa1252b87367c1824f46c9b1a/moveit_ros/moveit_servo/test/launch/servo_launch_test_common.py#L92
63+
description='Binary directory of package containing test executables'),
64+
# other fixture actions
65+
static_tranform_publisher,
66+
aruco_detect,
67+
fiducial_slam,
68+
test_node,
69+
#launch_testing.util.KeepAliveProc(), # From https://github.com/ros2/geometry2/blob/a1be44fdbd8c032351ffd3ddff8467d000f4c6d7/test_tf2/test/buffer_client_tester.launch.py#L39
70+
launch_testing.actions.ReadyToTest(),
71+
]), locals()
72+
73+
74+
class TestTestTermination(unittest.TestCase):
75+
def test_termination(self, test_node, proc_output, proc_info):
76+
proc_info.assertWaitForShutdown(process=test_node, timeout=(30))
77+
78+
@launch_testing.post_shutdown_test()
79+
class TestProcessOutput(unittest.TestCase):
80+
def test_no_failed_tests(self, proc_output, proc_info, test_node):
81+
# Check that process exits with code -15 code: termination request, sent to the program
82+
number_of_failed_tests = 0
83+
launch_testing.asserts.assertExitCodes(proc_info, [number_of_failed_tests], process=test_node)

fiducial_slam/test/auto_init_403_test.cpp

Lines changed: 66 additions & 59 deletions
Original file line numberDiff line numberDiff line change
@@ -6,25 +6,32 @@ and the map entry for the fiducial is reasonable
66

77
#include <gtest/gtest.h>
88

9-
#include <ros/ros.h>
10-
#include <image_transport/image_transport.h>
11-
#include <sensor_msgs/CameraInfo.h>
9+
#include <rclcpp/rclcpp.hpp>
10+
#include <rclcpp/node.hpp>
11+
12+
#include <image_transport/image_transport.hpp>
13+
#include <sensor_msgs/msg/camera_info.hpp>
1214
#include <opencv2/highgui/highgui.hpp>
1315
#include <cv_bridge/cv_bridge.h>
1416

15-
#include <geometry_msgs/PoseWithCovarianceStamped.h>
17+
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
1618

17-
#include <fiducial_msgs/FiducialMapEntry.h>
18-
#include <fiducial_msgs/FiducialMapEntryArray.h>
19+
#include "fiducial_msgs/msg/fiducial_map_entry.hpp"
20+
#include "fiducial_msgs/msg/fiducial_map_entry_array.hpp"
1921

2022

2123
class AutoInitTest : public ::testing::Test {
2224
protected:
23-
virtual void SetUp() {
24-
it = new image_transport::ImageTransport(nh);
25+
virtual void SetUp() {
26+
nh = std::make_shared<rclcpp::Node>("auto_init_403_test");
27+
28+
// Declare the parameters
29+
image_directory = nh->declare_parameter("image_directory", "");
30+
31+
it = std::make_shared<image_transport::ImageTransport>(nh);
2532
image_pub = it->advertise("camera/image", 1);
2633

27-
CameraInfoPub = nh.advertise<sensor_msgs::CameraInfo>("camera_info", 5);
34+
camera_info_pub = nh->create_publisher<sensor_msgs::msg::CameraInfo>("/camera/camera_info", 5);
2835

2936
c_info.header.frame_id = "camera";
3037
c_info.height = 960;
@@ -34,100 +41,101 @@ class AutoInitTest : public ::testing::Test {
3441
double data_D[] = {0.1349735087283542, -0.2335869827451621,
3542
0.0006697030315075139, 0.004846737465872353, 0.0};
3643

37-
c_info.D = std::vector<double> (data_D,
44+
c_info.d = std::vector<double> (data_D,
3845
data_D + sizeof(data_D)/ sizeof(double));
39-
40-
c_info.K = {1006.126285753055, 0.0, 655.8639244150409,
46+
47+
c_info.k = {1006.126285753055, 0.0, 655.8639244150409,
4148
0.0, 1004.015433012594, 490.6140221242933,
4249
0.0, 0.0, 1.0};
4350

44-
c_info.R = {1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0};
51+
c_info.r = {1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0};
4552

46-
c_info.P = {1021.54345703125, 0.0, 661.9091982335958, 0.0,
53+
c_info.p = {1021.54345703125, 0.0, 661.9091982335958, 0.0,
4754
0.0, 1025.251953125, 490.6380671707448, 0.0,
4855
0.0, 0.0, 1.0, 0.0};
4956

50-
ros::NodeHandle nh_priv("~");
51-
nh_priv.getParam("image_directory", image_directory);
57+
map_sub = nh->create_subscription<fiducial_msgs::msg::FiducialMapEntryArray>
58+
("/fiducial_map", 1, std::bind(&AutoInitTest::map_callback, this, std::placeholders::_1));
5259

53-
pose_sub = nh.subscribe("/fiducial_pose", 1,
54-
&AutoInitTest::pose_callback, this);
55-
got_pose = false;
5660

57-
fiducial_msgs::FiducialMapEntryArray map;
58-
59-
map_sub = nh.subscribe("/fiducial_map", 1,
60-
&AutoInitTest::map_callback, this);
61-
got_map = false;
61+
pose_sub = nh->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>
62+
("/fiducial_pose", 1, std::bind(&AutoInitTest::pose_callback, this, std::placeholders::_1));
6263
}
6364

64-
virtual void TearDown() { delete it;}
65-
6665
void publish_image(std::string file)
6766
{
68-
cv::Mat image = cv::imread(image_directory+file, CV_LOAD_IMAGE_COLOR);
69-
cv::waitKey(30);
70-
sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(),
71-
"bgr8", image).toImageMsg();
67+
cv::Mat image = cv::imread(image_directory+file, cv::IMREAD_COLOR);
68+
69+
if(image.data == NULL)
70+
{
71+
FAIL() << "Cannot open " << image_directory+file;
72+
}
73+
//cv::waitKey(30); // Should not be needed
74+
auto msg = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", image).toImageMsg();
7275
image_pub.publish(msg);
73-
c_info.header.stamp = rclcpp::Time::now();
74-
CameraInfoPub.publish(c_info);
76+
c_info.header.stamp = nh->get_clock()->now();
77+
camera_info_pub->publish(c_info);
7578
}
7679

77-
void map_callback(const fiducial_msgs::FiducialMapEntryArray& msg)
80+
void map_callback(const fiducial_msgs::msg::FiducialMapEntryArray::SharedPtr msg)
7881
{
7982
got_map = true;
8083
map = msg;
8184
}
8285

83-
void pose_callback(const geometry_msgs::PoseWithCovarianceStamped& msg)
86+
void pose_callback(const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg)
8487
{
8588
got_pose = true;
8689
pose = msg;
8790
}
8891

89-
ros::NodeHandle nh;
92+
rclcpp::Node::SharedPtr nh;
9093

9194
// Set up Publishing of static images
92-
image_transport::ImageTransport* it;
95+
std::shared_ptr<image_transport::ImageTransport> it;
9396
image_transport::Publisher image_pub;
9497

95-
sensor_msgs::CameraInfo c_info;
96-
ros::Publisher CameraInfoPub;
98+
sensor_msgs::msg::CameraInfo c_info;
99+
rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr camera_info_pub;
97100

98101
std::string image_directory;
99102

100-
ros::Subscriber map_sub;
101-
ros::Subscriber pose_sub;
103+
rclcpp::Subscription<fiducial_msgs::msg::FiducialMapEntryArray>::SharedPtr map_sub;
104+
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr pose_sub;
102105

103-
bool got_map;
104-
bool got_pose;
106+
bool got_map{false};
107+
bool got_pose{false};
105108

106-
fiducial_msgs::FiducialMapEntryArray map;
107-
geometry_msgs::PoseWithCovarianceStamped pose;
109+
fiducial_msgs::msg::FiducialMapEntryArray::SharedPtr map;
110+
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr pose;
108111

109112
};
110113

111114
TEST_F(AutoInitTest, tag_403_d7_14cm) {
112-
ros::Rate loop_rate(5);
113-
while (nh.ok() && (!got_pose || !got_map)) {
115+
int loop_count = 0;
116+
rclcpp::Rate loop_rate(5);
117+
while (rclcpp::ok() && (!got_pose || !got_map)) {
114118
publish_image("403.jpg");
115-
ros::spinOnce();
119+
rclcpp::spin_some(nh);
116120
loop_rate.sleep();
121+
loop_count++;
122+
if (loop_count > 100) {
123+
FAIL() << "Did not receive estimate within 10 frames";
124+
}
117125
}
118126

119-
ASSERT_NEAR(0, pose.pose.pose.position.x, 0.001);
120-
ASSERT_NEAR(0, pose.pose.pose.position.y, 0.001);
121-
ASSERT_NEAR(0, pose.pose.pose.position.z, 0.001);
127+
ASSERT_NEAR(0, pose->pose.pose.position.x, 0.001);
128+
ASSERT_NEAR(0, pose->pose.pose.position.y, 0.001);
129+
ASSERT_NEAR(0, pose->pose.pose.position.z, 0.001);
122130

123-
ASSERT_NEAR(1, pose.pose.pose.orientation.w, 0.001);
124-
ASSERT_NEAR(0, pose.pose.pose.orientation.x, 0.001);
125-
ASSERT_NEAR(0, pose.pose.pose.orientation.y, 0.001);
126-
ASSERT_NEAR(0, pose.pose.pose.orientation.z, 0.001);
131+
ASSERT_NEAR(1, pose->pose.pose.orientation.w, 0.001);
132+
ASSERT_NEAR(0, pose->pose.pose.orientation.x, 0.001);
133+
ASSERT_NEAR(0, pose->pose.pose.orientation.y, 0.001);
134+
ASSERT_NEAR(0, pose->pose.pose.orientation.z, 0.001);
127135

128-
ASSERT_LE(1, map.fiducials.size());
129-
130-
const fiducial_msgs::FiducialMapEntry &fid = map.fiducials[0];
136+
ASSERT_LE(1, map->fiducials.size());
137+
138+
const fiducial_msgs::msg::FiducialMapEntry &fid = map->fiducials[0];
131139
ASSERT_EQ(403, fid.fiducial_id);
132140
ASSERT_NEAR(0.7611, fid.x, 0.001);
133141
ASSERT_NEAR(0.2505, fid.y, 0.001);
@@ -139,8 +147,7 @@ TEST_F(AutoInitTest, tag_403_d7_14cm) {
139147

140148
int main(int argc, char** argv)
141149
{
142-
143150
testing::InitGoogleTest(&argc, argv);
144-
ros::init(argc, argv, "AutoInitTest");
151+
rclcpp::init(argc, argv);
145152
return RUN_ALL_TESTS();
146153
}

0 commit comments

Comments
 (0)