@@ -62,6 +62,13 @@ class GPSSensorBroadcasterTest : public ::testing::Test
6262
6363 ~GPSSensorBroadcasterTest () { rclcpp::shutdown (); }
6464
65+ void SetUp ()
66+ {
67+ gps_broadcaster_ = std::make_unique<gps_sensor_broadcaster::GPSSensorBroadcaster>();
68+ }
69+
70+ void TearDown () { gps_broadcaster_.reset (nullptr ); }
71+
6572 template <
6673 semantic_components::GPSSensorOption sensor_option =
6774 semantic_components::GPSSensorOption::WithoutCovariance>
@@ -80,7 +87,7 @@ class GPSSensorBroadcasterTest : public ::testing::Test
8087 state_ifs.emplace_back (altitude_covariance_);
8188 }
8289
83- gps_broadcaster_. assign_interfaces ({}, std::move (state_ifs));
90+ gps_broadcaster_-> assign_interfaces ({}, std::move (state_ifs));
8491 }
8592
8693 sensor_msgs::msg::NavSatFix subscribe_and_get_message ()
@@ -89,7 +96,7 @@ class GPSSensorBroadcasterTest : public ::testing::Test
8996 auto subscription = test_subscription_node.create_subscription <sensor_msgs::msg::NavSatFix>(
9097 " /test_gps_sensor_broadcaster/gps/fix" , 10 ,
9198 [](const sensor_msgs::msg::NavSatFix::SharedPtr) {});
92- gps_broadcaster_. update (rclcpp::Time{}, rclcpp::Duration::from_seconds (0 ));
99+ gps_broadcaster_-> update (rclcpp::Time{}, rclcpp::Duration::from_seconds (0 ));
93100 wait_for (subscription);
94101
95102 rclcpp::MessageInfo msg_info;
@@ -115,21 +122,21 @@ class GPSSensorBroadcasterTest : public ::testing::Test
115122 hardware_interface::StateInterface altitude_covariance_{
116123 sensor_name_, " altitude_covariance" , &sensor_values_[7 ]};
117124
118- gps_sensor_broadcaster::GPSSensorBroadcaster gps_broadcaster_;
125+ std::unique_ptr< gps_sensor_broadcaster::GPSSensorBroadcaster> gps_broadcaster_;
119126};
120127
121128TEST_F (GPSSensorBroadcasterTest, whenNoParamsAreSetThenInitShouldFail)
122129{
123- const auto result = gps_broadcaster_. init (
130+ const auto result = gps_broadcaster_-> init (
124131 " test_gps_sensor_broadcaster" , ros2_control_test_assets::minimal_robot_urdf, 0 , " " ,
125- gps_broadcaster_. define_custom_node_options ());
132+ gps_broadcaster_-> define_custom_node_options ());
126133 ASSERT_EQ (result, controller_interface::return_type::ERROR);
127134}
128135
129136TEST_F (GPSSensorBroadcasterTest, whenOnlySensorNameIsSetThenInitShouldFail)
130137{
131138 const auto node_options = create_node_options_with_overriden_parameters ({sensor_name_param_});
132- const auto result = gps_broadcaster_. init (
139+ const auto result = gps_broadcaster_-> init (
133140 " test_gps_sensor_broadcaster" , ros2_control_test_assets::minimal_robot_urdf, 0 , " " ,
134141 node_options);
135142 ASSERT_EQ (result, controller_interface::return_type::ERROR);
@@ -141,28 +148,30 @@ TEST_F(
141148{
142149 const auto node_options =
143150 create_node_options_with_overriden_parameters ({sensor_name_param_, frame_id_});
144- const auto result = gps_broadcaster_. init (
151+ const auto result = gps_broadcaster_-> init (
145152 " test_gps_sensor_broadcaster" , ros2_control_test_assets::minimal_robot_urdf, 0 , " " ,
146153 node_options);
147154 ASSERT_EQ (result, controller_interface::return_type::OK);
148155 ASSERT_EQ (
149- gps_broadcaster_.on_configure (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
150- ASSERT_EQ (gps_broadcaster_.on_activate (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
156+ gps_broadcaster_->on_configure (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
157+ ASSERT_EQ (
158+ gps_broadcaster_->on_activate (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
151159}
152160
153161TEST_F (
154162 GPSSensorBroadcasterTest, whenBroadcasterIsActiveShouldPublishNavSatMsgWithCovarianceSetToZero)
155163{
156164 const auto node_options =
157165 create_node_options_with_overriden_parameters ({sensor_name_param_, frame_id_});
158- const auto result = gps_broadcaster_. init (
166+ const auto result = gps_broadcaster_-> init (
159167 " test_gps_sensor_broadcaster" , ros2_control_test_assets::minimal_robot_urdf, 0 , " " ,
160168 node_options);
161169 ASSERT_EQ (result, controller_interface::return_type::OK);
162170 ASSERT_EQ (
163- gps_broadcaster_. on_configure (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
171+ gps_broadcaster_-> on_configure (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
164172 setup_gps_broadcaster ();
165- ASSERT_EQ (gps_broadcaster_.on_activate (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
173+ ASSERT_EQ (
174+ gps_broadcaster_->on_activate (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
166175
167176 const auto gps_msg = subscribe_and_get_message ();
168177 EXPECT_EQ (gps_msg.header .frame_id , frame_id_.get_value <std::string>());
@@ -186,14 +195,15 @@ TEST_F(
186195 frame_id_,
187196 {" static_position_covariance" ,
188197 std::vector<double >{static_covariance.begin (), static_covariance.end ()}}});
189- const auto result = gps_broadcaster_. init (
198+ const auto result = gps_broadcaster_-> init (
190199 " test_gps_sensor_broadcaster" , ros2_control_test_assets::minimal_robot_urdf, 0 , " " ,
191200 node_options);
192201 ASSERT_EQ (result, controller_interface::return_type::OK);
193202 ASSERT_EQ (
194- gps_broadcaster_. on_configure (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
203+ gps_broadcaster_-> on_configure (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
195204 setup_gps_broadcaster ();
196- ASSERT_EQ (gps_broadcaster_.on_activate (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
205+ ASSERT_EQ (
206+ gps_broadcaster_->on_activate (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
197207
198208 const auto gps_msg = subscribe_and_get_message ();
199209 EXPECT_EQ (gps_msg.header .frame_id , frame_id_.get_value <std::string>());
@@ -213,14 +223,15 @@ TEST_F(
213223{
214224 const auto node_options = create_node_options_with_overriden_parameters (
215225 {sensor_name_param_, frame_id_, {" read_covariance_from_interface" , true }});
216- const auto result = gps_broadcaster_. init (
226+ const auto result = gps_broadcaster_-> init (
217227 " test_gps_sensor_broadcaster" , ros2_control_test_assets::minimal_robot_urdf, 0 , " " ,
218228 node_options);
219229 ASSERT_EQ (result, controller_interface::return_type::OK);
220230 ASSERT_EQ (
221- gps_broadcaster_. on_configure (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
231+ gps_broadcaster_-> on_configure (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
222232 setup_gps_broadcaster<semantic_components::GPSSensorOption::WithCovariance>();
223- ASSERT_EQ (gps_broadcaster_.on_activate (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
233+ ASSERT_EQ (
234+ gps_broadcaster_->on_activate (rclcpp_lifecycle::State ()), callback_return_type::SUCCESS);
224235
225236 const auto gps_msg = subscribe_and_get_message ();
226237 EXPECT_EQ (gps_msg.header .frame_id , frame_id_.get_value <std::string>());
0 commit comments