@@ -196,7 +196,7 @@ class Tester : public ::testing::Test
196
196
197
197
// CollisionMonitor node
198
198
std::shared_ptr<CollisionMonitorWrapper> cm_;
199
- rclcpp::executors::SingleThreadedExecutor executor_;
199
+ rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
200
200
201
201
// Footprint publisher
202
202
nav2::Publisher<geometry_msgs::msg::PolygonStamped>::SharedPtr
@@ -234,7 +234,8 @@ class Tester : public ::testing::Test
234
234
Tester::Tester ()
235
235
{
236
236
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 ());
238
239
cm_->declare_parameter (" enable_stamped_cmd_vel" , rclcpp::ParameterValue (false ));
239
240
240
241
footprint_pub_ = cm_->create_publisher <geometry_msgs::msg::PolygonStamped>(
@@ -739,7 +740,7 @@ bool Tester::waitData(
739
740
if (cm_->correctDataReceived (expected_dist, stamp)) {
740
741
return true ;
741
742
}
742
- executor_. spin_some ();
743
+ executor_-> spin_some ();
743
744
std::this_thread::sleep_for (10ms);
744
745
}
745
746
return false ;
@@ -752,7 +753,7 @@ bool Tester::waitCmdVel(const std::chrono::nanoseconds & timeout)
752
753
if (cmd_vel_out_) {
753
754
return true ;
754
755
}
755
- executor_. spin_some ();
756
+ executor_-> spin_some ();
756
757
std::this_thread::sleep_for (10ms);
757
758
}
758
759
return false ;
@@ -768,7 +769,7 @@ bool Tester::waitFuture(
768
769
if (status == std::future_status::ready) {
769
770
return true ;
770
771
}
771
- executor_. spin_some ();
772
+ executor_-> spin_some ();
772
773
std::this_thread::sleep_for (10ms);
773
774
}
774
775
return false ;
@@ -784,7 +785,7 @@ bool Tester::waitToggle(
784
785
if (status == std::future_status::ready) {
785
786
return true ;
786
787
}
787
- executor_. spin_some ();
788
+ executor_-> spin_some ();
788
789
std::this_thread::sleep_for (10ms);
789
790
}
790
791
return false ;
@@ -797,7 +798,7 @@ bool Tester::waitActionState(const std::chrono::nanoseconds & timeout)
797
798
if (action_state_) {
798
799
return true ;
799
800
}
800
- executor_. spin_some ();
801
+ executor_-> spin_some ();
801
802
std::this_thread::sleep_for (10ms);
802
803
}
803
804
return false ;
@@ -810,7 +811,7 @@ bool Tester::waitCollisionPointsMarker(const std::chrono::nanoseconds & timeout)
810
811
if (collision_points_marker_msg_) {
811
812
return true ;
812
813
}
813
- executor_. spin_some ();
814
+ executor_-> spin_some ();
814
815
std::this_thread::sleep_for (10ms);
815
816
}
816
817
return false ;
0 commit comments