Skip to content

Commit f1a1f42

Browse files
authored
Fix fuse optimizer unit test (#369)
* Fix fuse optimizer unit test. The rclcpp::wait_for_message call was throwing an exception 'subscription already associated with a wait set'. Switched to a standard subscriber instead.
1 parent 6b3b5d3 commit f1a1f42

File tree

1 file changed

+38
-10
lines changed

1 file changed

+38
-10
lines changed

fuse_optimizers/test/launch_tests/test_fixed_lag_ignition.cpp

+38-10
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,10 @@
3333
*/
3434
#include <gtest/gtest.h>
3535

36+
#include <memory>
37+
#include <mutex>
38+
#include <thread>
39+
3640
#include <fuse_msgs/srv/set_pose.hpp>
3741
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
3842
#include <nav_msgs/msg/odometry.hpp>
@@ -65,8 +69,22 @@ class FixedLagIgnitionFixture : public ::testing::Test
6569
executor_.reset();
6670
}
6771

72+
void odom_callback(const nav_msgs::msg::Odometry::SharedPtr msg)
73+
{
74+
std::lock_guard lock(received_odom_mutex_);
75+
received_odom_msg_ = msg;
76+
}
77+
78+
nav_msgs::msg::Odometry::SharedPtr get_last_odom_msg()
79+
{
80+
std::lock_guard lock(received_odom_mutex_);
81+
return received_odom_msg_;
82+
}
83+
6884
std::thread spinner_; //!< Internal thread for spinning the executor
6985
rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
86+
nav_msgs::msg::Odometry::SharedPtr received_odom_msg_;
87+
std::mutex received_odom_mutex_;
7088
};
7189

7290
TEST_F(FixedLagIgnitionFixture, SetInitialState)
@@ -78,6 +96,10 @@ TEST_F(FixedLagIgnitionFixture, SetInitialState)
7896
node->create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
7997
"/relative_pose", 5);
8098

99+
auto odom_subscriber =
100+
node->create_subscription<nav_msgs::msg::Odometry>(
101+
"/odom", 5, std::bind(&FixedLagIgnitionFixture::odom_callback, this, std::placeholders::_1));
102+
81103
// Time should be valid after rclcpp::init() returns in main(). But it doesn't hurt to verify.
82104
ASSERT_TRUE(node->get_clock()->wait_until_started(rclcpp::Duration::from_seconds(1.0)));
83105

@@ -131,6 +153,10 @@ TEST_F(FixedLagIgnitionFixture, SetInitialState)
131153
pose_msg1.pose.covariance[35] = 1.0;
132154
relative_pose_publisher->publish(pose_msg1);
133155

156+
/// @todo(swilliams) Understand why the subscriber does not receive all the messages
157+
/// unless I force a delay between publishing.
158+
rclcpp::sleep_for(std::chrono::milliseconds(100));
159+
134160
auto pose_msg2 = geometry_msgs::msg::PoseWithCovarianceStamped();
135161
pose_msg2.header.stamp = rclcpp::Time(3, 0, RCL_ROS_TIME);
136162
pose_msg2.header.frame_id = "base_link";
@@ -146,23 +172,25 @@ TEST_F(FixedLagIgnitionFixture, SetInitialState)
146172
pose_msg2.pose.covariance[35] = 1.0;
147173
relative_pose_publisher->publish(pose_msg2);
148174

149-
// Wait for the optimizer to process all queued transactions
175+
// Wait for the optimizer to process all queued transactions and publish the last odometry msg
150176
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))
177+
auto odom_msg = nav_msgs::msg::Odometry::SharedPtr();
178+
while ((!odom_msg || odom_msg->header.stamp != rclcpp::Time(3, 0,
179+
RCL_ROS_TIME)) && (node->now() < result_timeout))
154180
{
155-
rclcpp::wait_for_message(odom_msg, node, "/odom", std::chrono::seconds(1));
181+
rclcpp::sleep_for(std::chrono::milliseconds(100));
182+
odom_msg = this->get_last_odom_msg();
156183
}
157-
ASSERT_EQ(rclcpp::Time(odom_msg.header.stamp), rclcpp::Time(3, 0, RCL_ROS_TIME));
184+
ASSERT_TRUE(static_cast<bool>(odom_msg));
185+
ASSERT_EQ(rclcpp::Time(odom_msg->header.stamp), rclcpp::Time(3, 0, RCL_ROS_TIME));
158186

159187
// The optimizer is configured for 0 iterations, so it should return the initial variable values
160188
// If we did our job correctly, the initial variable values should be the same as the service call
161189
// 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);
190+
EXPECT_NEAR(100.1, odom_msg->pose.pose.position.x, 0.10);
191+
EXPECT_NEAR(100.2, odom_msg->pose.pose.position.y, 0.10);
192+
EXPECT_NEAR(0.8660, odom_msg->pose.pose.orientation.z, 0.10);
193+
EXPECT_NEAR(0.5000, odom_msg->pose.pose.orientation.w, 0.10);
166194
}
167195

168196
// NOTE(CH3): This main is required because the test is manually run by a launch test

0 commit comments

Comments
 (0)