Skip to content

Commit 5715e8f

Browse files
committed
Improved parameter_handler usage when re-configure
1 parent 9cee59e commit 5715e8f

File tree

2 files changed

+25
-16
lines changed

2 files changed

+25
-16
lines changed

include/control_filters/gravity_compensation.hpp

+17-14
Original file line numberDiff line numberDiff line change
@@ -100,21 +100,24 @@ bool GravityCompensation<T>::configure()
100100
logger_.reset(
101101
new rclcpp::Logger(this->logging_interface_->get_logger().get_child(this->filter_name_)));
102102

103-
// Initialize the parameters
104-
try
103+
// Initialize the parameter_listener once
104+
if (!parameter_handler_)
105105
{
106-
parameter_handler_ =
107-
std::make_shared<gravity_compensation_filter::ParamListener>(this->params_interface_);
108-
}
109-
catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
110-
RCLCPP_ERROR((*logger_), "GravityCompensation filter cannot be configured: %s", ex.what());
111-
parameter_handler_.reset();
112-
return false;
113-
}
114-
catch (rclcpp::exceptions::InvalidParameterValueException & ex) {
115-
RCLCPP_ERROR((*logger_), "GravityCompensation filter cannot be configured: %s", ex.what());
116-
parameter_handler_.reset();
117-
return false;
106+
try
107+
{
108+
parameter_handler_ =
109+
std::make_shared<gravity_compensation_filter::ParamListener>(this->params_interface_);
110+
}
111+
catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
112+
RCLCPP_ERROR((*logger_), "GravityCompensation filter cannot be configured: %s", ex.what());
113+
parameter_handler_.reset();
114+
return false;
115+
}
116+
catch (rclcpp::exceptions::InvalidParameterValueException & ex) {
117+
RCLCPP_ERROR((*logger_), "GravityCompensation filter cannot be configured: %s", ex.what());
118+
parameter_handler_.reset();
119+
return false;
120+
}
118121
}
119122
parameters_ = parameter_handler_->get_params();
120123
compute_internal_params();

test/control_filters/test_gravity_compensation.cpp

+8-2
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ TEST_F(GravityCompensationTest, TestGravityCompensationMissingParameters)
3131
*/
3232
}
3333

34-
TEST_F(GravityCompensationTest, TestGravityCompensationInvalidParameters)
34+
TEST_F(GravityCompensationTest, TestGravityCompensationParameters)
3535
{
3636
std::shared_ptr<filters::FilterBase<geometry_msgs::msg::WrenchStamped>> filter_ =
3737
std::make_shared<control_filters::GravityCompensation<geometry_msgs::msg::WrenchStamped>>();
@@ -49,7 +49,13 @@ TEST_F(GravityCompensationTest, TestGravityCompensationInvalidParameters)
4949
node_->get_node_logging_interface(), node_->get_node_parameters_interface()));
5050

5151
node_->set_parameter(rclcpp::Parameter("CoG.pos", std::vector<double>({0.0, 0.0, 0.0})));
52-
// all parameters correctly set
52+
// all parameters correctly set AND second call to yet unconfigured filter
53+
ASSERT_TRUE(filter_->configure("", "TestGravityCompensationFilter",
54+
node_->get_node_logging_interface(), node_->get_node_parameters_interface()));
55+
56+
// change a parameter
57+
node_->set_parameter(rclcpp::Parameter("CoG.pos", std::vector<double>({0.0, 0.0, 0.2})));
58+
// accept second call to configure with valid parameters to already configured filter
5359
ASSERT_TRUE(filter_->configure("", "TestGravityCompensationFilter",
5460
node_->get_node_logging_interface(), node_->get_node_parameters_interface()));
5561
}

0 commit comments

Comments
 (0)