@@ -6,25 +6,32 @@ and the map entry for the fiducial is reasonable
6
6
7
7
#include < gtest/gtest.h>
8
8
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>
12
14
#include < opencv2/highgui/highgui.hpp>
13
15
#include < cv_bridge/cv_bridge.h>
14
16
15
- #include < geometry_msgs/PoseWithCovarianceStamped.h >
17
+ #include < geometry_msgs/msg/pose_with_covariance_stamped.hpp >
16
18
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 "
19
21
20
22
21
23
class AutoInitTest : public ::testing::Test {
22
24
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);
25
32
image_pub = it->advertise (" camera/image" , 1 );
26
33
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 );
28
35
29
36
c_info.header .frame_id = " camera" ;
30
37
c_info.height = 960 ;
@@ -34,100 +41,101 @@ class AutoInitTest : public ::testing::Test {
34
41
double data_D[] = {0.1349735087283542 , -0.2335869827451621 ,
35
42
0.0006697030315075139 , 0.004846737465872353 , 0.0 };
36
43
37
- c_info.D = std::vector<double > (data_D,
44
+ c_info.d = std::vector<double > (data_D,
38
45
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 ,
41
48
0.0 , 1004.015433012594 , 490.6140221242933 ,
42
49
0.0 , 0.0 , 1.0 };
43
50
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 };
45
52
46
- c_info.P = {1021.54345703125 , 0.0 , 661.9091982335958 , 0.0 ,
53
+ c_info.p = {1021.54345703125 , 0.0 , 661.9091982335958 , 0.0 ,
47
54
0.0 , 1025.251953125 , 490.6380671707448 , 0.0 ,
48
55
0.0 , 0.0 , 1.0 , 0.0 };
49
56
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) );
52
59
53
- pose_sub = nh.subscribe (" /fiducial_pose" , 1 ,
54
- &AutoInitTest::pose_callback, this );
55
- got_pose = false ;
56
60
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));
62
63
}
63
64
64
- virtual void TearDown () { delete it;}
65
-
66
65
void publish_image (std::string file)
67
66
{
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 ();
72
75
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);
75
78
}
76
79
77
- void map_callback (const fiducial_msgs::FiducialMapEntryArray& msg)
80
+ void map_callback (const fiducial_msgs::msg:: FiducialMapEntryArray::SharedPtr msg)
78
81
{
79
82
got_map = true ;
80
83
map = msg;
81
84
}
82
85
83
- void pose_callback (const geometry_msgs::PoseWithCovarianceStamped& msg)
86
+ void pose_callback (const geometry_msgs::msg:: PoseWithCovarianceStamped::SharedPtr msg)
84
87
{
85
88
got_pose = true ;
86
89
pose = msg;
87
90
}
88
91
89
- ros::NodeHandle nh;
92
+ rclcpp::Node::SharedPtr nh;
90
93
91
94
// Set up Publishing of static images
92
- image_transport::ImageTransport* it;
95
+ std::shared_ptr< image_transport::ImageTransport> it;
93
96
image_transport::Publisher image_pub;
94
97
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 ;
97
100
98
101
std::string image_directory;
99
102
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;
102
105
103
- bool got_map;
104
- bool got_pose;
106
+ bool got_map{ false } ;
107
+ bool got_pose{ false } ;
105
108
106
- fiducial_msgs::FiducialMapEntryArray map;
107
- geometry_msgs::PoseWithCovarianceStamped pose;
109
+ fiducial_msgs::msg:: FiducialMapEntryArray::SharedPtr map;
110
+ geometry_msgs::msg:: PoseWithCovarianceStamped::SharedPtr pose;
108
111
109
112
};
110
113
111
114
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)) {
114
118
publish_image (" 403.jpg" );
115
- ros::spinOnce ( );
119
+ rclcpp::spin_some (nh );
116
120
loop_rate.sleep ();
121
+ loop_count++;
122
+ if (loop_count > 100 ) {
123
+ FAIL () << " Did not receive estimate within 10 frames" ;
124
+ }
117
125
}
118
126
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 );
122
130
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 );
127
135
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 ];
131
139
ASSERT_EQ (403 , fid.fiducial_id );
132
140
ASSERT_NEAR (0.7611 , fid.x , 0.001 );
133
141
ASSERT_NEAR (0.2505 , fid.y , 0.001 );
@@ -139,8 +147,7 @@ TEST_F(AutoInitTest, tag_403_d7_14cm) {
139
147
140
148
int main (int argc, char ** argv)
141
149
{
142
-
143
150
testing::InitGoogleTest (&argc, argv);
144
- ros ::init (argc, argv, " AutoInitTest " );
151
+ rclcpp ::init (argc, argv);
145
152
return RUN_ALL_TESTS ();
146
153
}
0 commit comments