Skip to content

Commit 7a9ce64

Browse files
Add set_custom_node_parameters
1 parent bcaf5ab commit 7a9ce64

File tree

2 files changed

+6
-12
lines changed

2 files changed

+6
-12
lines changed

kinematics_interface/test/kinematics_interface_common_tests.hpp

Lines changed: 2 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -56,10 +56,11 @@ class TestPlugin : public ::testing::Test
5656
ik_loader_->createUnmanagedInstance(plugin_name));
5757

5858
node_->declare_parameter("verbose", true);
59-
node_->declare_parameter("alpha", 0.005);
6059
node_->declare_parameter("robot_description", urdf_);
6160
node_->declare_parameter("tip", end_effector_);
6261
node_->declare_parameter("base", std::string(""));
62+
63+
PluginUnderTest::set_custom_node_parameters(node_);
6364
}
6465

6566
void TearDown()
@@ -80,17 +81,6 @@ class TestPlugin : public ::testing::Test
8081
node_->set_parameter(param);
8182
}
8283

83-
/**
84-
* \brief Used for testing initialization from parameters.
85-
* Elsewhere, default 0.005 is used.
86-
*/
87-
88-
void loadAlphaParameter(double alpha)
89-
{
90-
rclcpp::Parameter param("alpha", alpha);
91-
node_->set_parameter(param);
92-
}
93-
9484
/**
9585
* \brief Used for testing initialization from parameters.
9686
* Elsewhere, `end_effector_` member is used.

kinematics_interface_kdl/test/test_kinematics_interface_kdl.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,10 @@
2121
struct PluginKDL
2222
{
2323
static std::string Name() { return "kinematics_interface_kdl/KinematicsInterfaceKDL"; }
24+
static void set_custom_node_parameters(rclcpp_lifecycle::LifecycleNode::SharedPtr node)
25+
{
26+
node->declare_parameter("alpha", 0.005);
27+
}
2428
};
2529

2630
using MyTypes = ::testing::Types<PluginKDL>;

0 commit comments

Comments
 (0)