@@ -28,6 +28,10 @@ class JointLimitsRosParamTest : public ::testing::Test
28
28
rclcpp::NodeOptions node_options;
29
29
node_options.allow_undeclared_parameters (true ).automatically_declare_parameters_from_overrides (
30
30
true );
31
+ const std::vector<std::string> node_option_arguments = {
32
+ " --ros-args" , " --params-file" ,
33
+ std::string (PARAMETERS_FILE_PATH) + std::string (" joint_limits_rosparam.yaml" )};
34
+ node_options.arguments (node_option_arguments);
31
35
32
36
node_ = rclcpp::Node::make_shared (" JointLimitsRosparamTestNode" , node_options);
33
37
}
@@ -279,7 +283,16 @@ TEST_F(JointLimitsRosParamTest, parse_soft_joint_limits)
279
283
class JointLimitsUndeclaredRosParamTest : public ::testing::Test
280
284
{
281
285
public:
282
- void SetUp () { node_ = rclcpp::Node::make_shared (" JointLimitsRosparamTestNode" ); }
286
+ void SetUp ()
287
+ {
288
+ rclcpp::NodeOptions node_options;
289
+ const std::vector<std::string> node_option_arguments = {
290
+ " --ros-args" , " --params-file" ,
291
+ std::string (PARAMETERS_FILE_PATH) + std::string (" joint_limits_rosparam.yaml" )};
292
+ node_options.arguments (node_option_arguments);
293
+
294
+ node_ = rclcpp::Node::make_shared (" JointLimitsRosparamTestNode" , node_options);
295
+ }
283
296
284
297
void TearDown () { node_.reset (); }
285
298
@@ -292,7 +305,14 @@ class JointLimitsLifecycleNodeUndeclaredRosParamTest : public ::testing::Test
292
305
public:
293
306
void SetUp ()
294
307
{
295
- lifecycle_node_ = rclcpp_lifecycle::LifecycleNode::make_shared (" JointLimitsRosparamTestNode" );
308
+ rclcpp::NodeOptions node_options;
309
+ const std::vector<std::string> node_option_arguments = {
310
+ " --ros-args" , " --params-file" ,
311
+ std::string (PARAMETERS_FILE_PATH) + std::string (" joint_limits_rosparam.yaml" )};
312
+ node_options.arguments (node_option_arguments);
313
+
314
+ lifecycle_node_ =
315
+ rclcpp_lifecycle::LifecycleNode::make_shared (" JointLimitsRosparamTestNode" , node_options);
296
316
}
297
317
298
318
void TearDown ()
0 commit comments