Skip to content

Commit d8cc774

Browse files
committed
Changed to main branch implementation
Signed-off-by: Abhishekh Reddy <[email protected]>
1 parent 5f82fe5 commit d8cc774

File tree

1 file changed

+9
-8
lines changed

1 file changed

+9
-8
lines changed

nav2_collision_monitor/test/collision_monitor_node_test.cpp

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -196,7 +196,7 @@ class Tester : public ::testing::Test
196196

197197
// CollisionMonitor node
198198
std::shared_ptr<CollisionMonitorWrapper> cm_;
199-
rclcpp::executors::SingleThreadedExecutor executor_;
199+
rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
200200

201201
// Footprint publisher
202202
nav2::Publisher<geometry_msgs::msg::PolygonStamped>::SharedPtr
@@ -234,7 +234,8 @@ class Tester : public ::testing::Test
234234
Tester::Tester()
235235
{
236236
cm_ = std::make_shared<CollisionMonitorWrapper>();
237-
executor_.add_node(cm_->get_node_base_interface());
237+
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
238+
executor_->add_node(cm_->get_node_base_interface());
238239
cm_->declare_parameter("enable_stamped_cmd_vel", rclcpp::ParameterValue(false));
239240

240241
footprint_pub_ = cm_->create_publisher<geometry_msgs::msg::PolygonStamped>(
@@ -739,7 +740,7 @@ bool Tester::waitData(
739740
if (cm_->correctDataReceived(expected_dist, stamp)) {
740741
return true;
741742
}
742-
executor_.spin_some();
743+
executor_->spin_some();
743744
std::this_thread::sleep_for(10ms);
744745
}
745746
return false;
@@ -752,7 +753,7 @@ bool Tester::waitCmdVel(const std::chrono::nanoseconds & timeout)
752753
if (cmd_vel_out_) {
753754
return true;
754755
}
755-
executor_.spin_some();
756+
executor_->spin_some();
756757
std::this_thread::sleep_for(10ms);
757758
}
758759
return false;
@@ -768,7 +769,7 @@ bool Tester::waitFuture(
768769
if (status == std::future_status::ready) {
769770
return true;
770771
}
771-
executor_.spin_some();
772+
executor_->spin_some();
772773
std::this_thread::sleep_for(10ms);
773774
}
774775
return false;
@@ -784,7 +785,7 @@ bool Tester::waitToggle(
784785
if (status == std::future_status::ready) {
785786
return true;
786787
}
787-
executor_.spin_some();
788+
executor_->spin_some();
788789
std::this_thread::sleep_for(10ms);
789790
}
790791
return false;
@@ -797,7 +798,7 @@ bool Tester::waitActionState(const std::chrono::nanoseconds & timeout)
797798
if (action_state_) {
798799
return true;
799800
}
800-
executor_.spin_some();
801+
executor_->spin_some();
801802
std::this_thread::sleep_for(10ms);
802803
}
803804
return false;
@@ -810,7 +811,7 @@ bool Tester::waitCollisionPointsMarker(const std::chrono::nanoseconds & timeout)
810811
if (collision_points_marker_msg_) {
811812
return true;
812813
}
813-
executor_.spin_some();
814+
executor_->spin_some();
814815
std::this_thread::sleep_for(10ms);
815816
}
816817
return false;

0 commit comments

Comments
 (0)