@@ -65,8 +65,14 @@ class FixedLagIgnitionFixture : public ::testing::Test
6565 executor_.reset ();
6666 }
6767
68+ void odom_callback (const nav_msgs::msg::Odometry::SharedPtr msg)
69+ {
70+ received_odom_msg_ = msg;
71+ }
72+
6873 std::thread spinner_; // !< Internal thread for spinning the executor
6974 rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
75+ nav_msgs::msg::Odometry::SharedPtr received_odom_msg_;
7076};
7177
7278TEST_F (FixedLagIgnitionFixture, SetInitialState)
@@ -78,6 +84,10 @@ TEST_F(FixedLagIgnitionFixture, SetInitialState)
7884 node->create_publisher <geometry_msgs::msg::PoseWithCovarianceStamped>(
7985 " /relative_pose" , 5 );
8086
87+ auto odom_subscriber =
88+ node->create_subscription <nav_msgs::msg::Odometry>(
89+ " /odom" , 5 , std::bind (&FixedLagIgnitionFixture::odom_callback, this , std::placeholders::_1));
90+
8191 // Time should be valid after rclcpp::init() returns in main(). But it doesn't hurt to verify.
8292 ASSERT_TRUE (node->get_clock ()->wait_until_started (rclcpp::Duration::from_seconds (1.0 )));
8393
@@ -131,6 +141,10 @@ TEST_F(FixedLagIgnitionFixture, SetInitialState)
131141 pose_msg1.pose .covariance [35 ] = 1.0 ;
132142 relative_pose_publisher->publish (pose_msg1);
133143
144+ // / @todo(swilliams) Understand why the subscriber does not receive all the messages
145+ // / unless I force a delay between publishing.
146+ rclcpp::sleep_for (std::chrono::milliseconds (100 ));
147+
134148 auto pose_msg2 = geometry_msgs::msg::PoseWithCovarianceStamped ();
135149 pose_msg2.header .stamp = rclcpp::Time (3 , 0 , RCL_ROS_TIME);
136150 pose_msg2.header .frame_id = " base_link" ;
@@ -146,23 +160,22 @@ TEST_F(FixedLagIgnitionFixture, SetInitialState)
146160 pose_msg2.pose .covariance [35 ] = 1.0 ;
147161 relative_pose_publisher->publish (pose_msg2);
148162
149- // Wait for the optimizer to process all queued transactions
163+ // Wait for the optimizer to process all queued transactions and publish the last odometry msg
150164 rclcpp::Time result_timeout = node->now () + rclcpp::Duration::from_seconds (1.0 );
151- auto odom_msg = nav_msgs::msg::Odometry ();
152- while ((odom_msg.header .stamp != rclcpp::Time (3 , 0 , RCL_ROS_TIME)) &&
153- (node->now () < result_timeout))
165+ while ((!received_odom_msg_ || received_odom_msg_->header .stamp != rclcpp::Time (3 , 0 ,
166+ RCL_ROS_TIME)) && (node->now () < result_timeout))
154167 {
155- rclcpp::wait_for_message (odom_msg, node, " /odom " , std::chrono::seconds ( 1 ));
168+ rclcpp::sleep_for ( std::chrono::milliseconds ( 100 ));
156169 }
157- ASSERT_EQ (rclcpp::Time (odom_msg. header .stamp ), rclcpp::Time (3 , 0 , RCL_ROS_TIME));
170+ ASSERT_EQ (rclcpp::Time (received_odom_msg_-> header .stamp ), rclcpp::Time (3 , 0 , RCL_ROS_TIME));
158171
159172 // The optimizer is configured for 0 iterations, so it should return the initial variable values
160173 // If we did our job correctly, the initial variable values should be the same as the service call
161174 // state, give or take the motion model forward prediction.
162- EXPECT_NEAR (100.1 , odom_msg. pose .pose .position .x , 0.10 );
163- EXPECT_NEAR (100.2 , odom_msg. pose .pose .position .y , 0.10 );
164- EXPECT_NEAR (0.8660 , odom_msg. pose .pose .orientation .z , 0.10 );
165- EXPECT_NEAR (0.5000 , odom_msg. pose .pose .orientation .w , 0.10 );
175+ EXPECT_NEAR (100.1 , received_odom_msg_-> pose .pose .position .x , 0.10 );
176+ EXPECT_NEAR (100.2 , received_odom_msg_-> pose .pose .position .y , 0.10 );
177+ EXPECT_NEAR (0.8660 , received_odom_msg_-> pose .pose .orientation .z , 0.10 );
178+ EXPECT_NEAR (0.5000 , received_odom_msg_-> pose .pose .orientation .w , 0.10 );
166179}
167180
168181// NOTE(CH3): This main is required because the test is manually run by a launch test
0 commit comments