@@ -118,6 +118,166 @@ TEST_F(MecanumDriveControllerTest, when_controller_configured_expect_properly_ex
118
118
}
119
119
}
120
120
121
+ TEST_F (MecanumDriveControllerTest, configure_succeeds_tf_test_prefix_false_no_namespace)
122
+ {
123
+ std::string odom_id = " odom" ;
124
+ std::string base_link_id = " base_link" ;
125
+ std::string frame_prefix = " test_prefix" ;
126
+
127
+ auto node_options = controller_->define_custom_node_options ();
128
+ node_options.append_parameter_override (" tf_frame_prefix_enable" , rclcpp::ParameterValue (false ));
129
+ node_options.append_parameter_override (" tf_frame_prefix" , rclcpp::ParameterValue (frame_prefix));
130
+ node_options.append_parameter_override (" odom_frame_id" , rclcpp::ParameterValue (odom_id));
131
+ node_options.append_parameter_override (" base_frame_id" , rclcpp::ParameterValue (base_link_id));
132
+
133
+ SetUpController (" test_mecanum_drive_controller" , node_options);
134
+
135
+ ASSERT_EQ (controller_->on_configure (rclcpp_lifecycle::State ()), NODE_SUCCESS);
136
+
137
+ auto odometry_message = controller_->get_rt_odom_state_publisher_msg ();
138
+ std::string test_odom_frame_id = odometry_message.header .frame_id ;
139
+ std::string test_base_frame_id = odometry_message.child_frame_id ;
140
+ /* tf_frame_prefix_enable is false so no modifications to the frame id's */
141
+ ASSERT_EQ (test_odom_frame_id, odom_id);
142
+ ASSERT_EQ (test_base_frame_id, base_link_id);
143
+ }
144
+
145
+ TEST_F (MecanumDriveControllerTest, configure_succeeds_tf_test_prefix_true_no_namespace)
146
+ {
147
+ std::string odom_id = " odom" ;
148
+ std::string base_link_id = " base_link" ;
149
+ std::string frame_prefix = " test_prefix" ;
150
+
151
+ auto node_options = controller_->define_custom_node_options ();
152
+ node_options.append_parameter_override (" tf_frame_prefix_enable" , rclcpp::ParameterValue (true ));
153
+ node_options.append_parameter_override (" tf_frame_prefix" , rclcpp::ParameterValue (frame_prefix));
154
+ node_options.append_parameter_override (" odom_frame_id" , rclcpp::ParameterValue (odom_id));
155
+ node_options.append_parameter_override (" base_frame_id" , rclcpp::ParameterValue (base_link_id));
156
+
157
+ SetUpController (" test_mecanum_drive_controller" , node_options);
158
+
159
+ ASSERT_EQ (controller_->on_configure (rclcpp_lifecycle::State ()), NODE_SUCCESS);
160
+
161
+ auto odometry_message = controller_->get_rt_odom_state_publisher_msg ();
162
+ std::string test_odom_frame_id = odometry_message.header .frame_id ;
163
+ std::string test_base_frame_id = odometry_message.child_frame_id ;
164
+
165
+ /* tf_frame_prefix_enable is true and frame_prefix is not blank so should be appended to the
166
+ frame
167
+ * id's */
168
+ ASSERT_EQ (test_odom_frame_id, frame_prefix + " /" + odom_id);
169
+ ASSERT_EQ (test_base_frame_id, frame_prefix + " /" + base_link_id);
170
+ }
171
+
172
+ TEST_F (MecanumDriveControllerTest, configure_succeeds_tf_blank_prefix_true_no_namespace)
173
+ {
174
+ std::string odom_id = " odom" ;
175
+ std::string base_link_id = " base_link" ;
176
+ std::string frame_prefix = " " ;
177
+
178
+ auto node_options = controller_->define_custom_node_options ();
179
+ node_options.append_parameter_override (" tf_frame_prefix_enable" , rclcpp::ParameterValue (true ));
180
+ node_options.append_parameter_override (" tf_frame_prefix" , rclcpp::ParameterValue (frame_prefix));
181
+ node_options.append_parameter_override (" odom_frame_id" , rclcpp::ParameterValue (odom_id));
182
+ node_options.append_parameter_override (" base_frame_id" , rclcpp::ParameterValue (base_link_id));
183
+
184
+ SetUpController (" test_mecanum_drive_controller" , node_options);
185
+
186
+ ASSERT_EQ (controller_->on_configure (rclcpp_lifecycle::State ()), NODE_SUCCESS);
187
+
188
+ auto odometry_message = controller_->get_rt_odom_state_publisher_msg ();
189
+ std::string test_odom_frame_id = odometry_message.header .frame_id ;
190
+ std::string test_base_frame_id = odometry_message.child_frame_id ;
191
+ /* tf_frame_prefix_enable is true but frame_prefix is blank so should not be appended to the
192
+ frame
193
+ * id's */
194
+ ASSERT_EQ (test_odom_frame_id, odom_id);
195
+ ASSERT_EQ (test_base_frame_id, base_link_id);
196
+ }
197
+
198
+ TEST_F (MecanumDriveControllerTest, configure_succeeds_tf_test_prefix_false_set_namespace)
199
+ {
200
+ std::string test_namespace = " /test_namespace" ;
201
+
202
+ std::string odom_id = " odom" ;
203
+ std::string base_link_id = " base_link" ;
204
+ std::string frame_prefix = " test_prefix" ;
205
+
206
+ auto node_options = controller_->define_custom_node_options ();
207
+ node_options.append_parameter_override (" tf_frame_prefix_enable" , rclcpp::ParameterValue (false ));
208
+ node_options.append_parameter_override (" tf_frame_prefix" , rclcpp::ParameterValue (frame_prefix));
209
+ node_options.append_parameter_override (" odom_frame_id" , rclcpp::ParameterValue (odom_id));
210
+ node_options.append_parameter_override (" base_frame_id" , rclcpp::ParameterValue (base_link_id));
211
+
212
+ SetUpController (" test_mecanum_drive_controller" , node_options, test_namespace);
213
+
214
+ ASSERT_EQ (controller_->on_configure (rclcpp_lifecycle::State ()), NODE_SUCCESS);
215
+
216
+ auto odometry_message = controller_->get_rt_odom_state_publisher_msg ();
217
+ std::string test_odom_frame_id = odometry_message.header .frame_id ;
218
+ std::string test_base_frame_id = odometry_message.child_frame_id ;
219
+ /* tf_frame_prefix_enable is false so no modifications to the frame id's */
220
+ ASSERT_EQ (test_odom_frame_id, odom_id);
221
+ ASSERT_EQ (test_base_frame_id, base_link_id);
222
+ }
223
+
224
+ TEST_F (MecanumDriveControllerTest, configure_succeeds_tf_test_prefix_true_set_namespace)
225
+ {
226
+ std::string test_namespace = " /test_namespace" ;
227
+
228
+ std::string odom_id = " odom" ;
229
+ std::string base_link_id = " base_link" ;
230
+ std::string frame_prefix = " test_prefix" ;
231
+
232
+ auto node_options = controller_->define_custom_node_options ();
233
+ node_options.append_parameter_override (" tf_frame_prefix_enable" , rclcpp::ParameterValue (true ));
234
+ node_options.append_parameter_override (" tf_frame_prefix" , rclcpp::ParameterValue (frame_prefix));
235
+ node_options.append_parameter_override (" odom_frame_id" , rclcpp::ParameterValue (odom_id));
236
+ node_options.append_parameter_override (" base_frame_id" , rclcpp::ParameterValue (base_link_id));
237
+
238
+ SetUpController (" test_mecanum_drive_controller" , node_options, test_namespace);
239
+
240
+ ASSERT_EQ (controller_->on_configure (rclcpp_lifecycle::State ()), NODE_SUCCESS);
241
+
242
+ auto odometry_message = controller_->get_rt_odom_state_publisher_msg ();
243
+ std::string test_odom_frame_id = odometry_message.header .frame_id ;
244
+ std::string test_base_frame_id = odometry_message.child_frame_id ;
245
+
246
+ /* tf_frame_prefix_enable is true and frame_prefix is not blank so should be appended to the
247
+ frame
248
+ * id's instead of the namespace*/
249
+ ASSERT_EQ (test_odom_frame_id, frame_prefix + " /" + odom_id);
250
+ ASSERT_EQ (test_base_frame_id, frame_prefix + " /" + base_link_id);
251
+ }
252
+
253
+ TEST_F (MecanumDriveControllerTest, configure_succeeds_tf_blank_prefix_true_set_namespace)
254
+ {
255
+ std::string test_namespace = " /test_namespace" ;
256
+ std::string odom_id = " odom" ;
257
+ std::string base_link_id = " base_link" ;
258
+ std::string frame_prefix = " " ;
259
+
260
+ auto node_options = controller_->define_custom_node_options ();
261
+ node_options.append_parameter_override (" tf_frame_prefix_enable" , rclcpp::ParameterValue (true ));
262
+ node_options.append_parameter_override (" tf_frame_prefix" , rclcpp::ParameterValue (frame_prefix));
263
+ node_options.append_parameter_override (" odom_frame_id" , rclcpp::ParameterValue (odom_id));
264
+ node_options.append_parameter_override (" base_frame_id" , rclcpp::ParameterValue (base_link_id));
265
+
266
+ SetUpController (" test_mecanum_drive_controller" , node_options, test_namespace);
267
+
268
+ ASSERT_EQ (controller_->on_configure (rclcpp_lifecycle::State ()), NODE_SUCCESS);
269
+
270
+ auto odometry_message = controller_->get_rt_odom_state_publisher_msg ();
271
+ std::string test_odom_frame_id = odometry_message.header .frame_id ;
272
+ std::string test_base_frame_id = odometry_message.child_frame_id ;
273
+ std::string ns_prefix = test_namespace.erase (0 , 1 ) + " /" ;
274
+ /* tf_frame_prefix_enable is true but frame_prefix is blank so namespace should be appended to
275
+ the
276
+ * frame id's */
277
+ ASSERT_EQ (test_odom_frame_id, ns_prefix + odom_id);
278
+ ASSERT_EQ (test_base_frame_id, ns_prefix + base_link_id);
279
+ }
280
+
121
281
TEST_F (MecanumDriveControllerTest, when_controller_is_activated_expect_reference_reset)
122
282
{
123
283
SetUpController ();
0 commit comments