@@ -31,7 +31,7 @@ TEST_F(GravityCompensationTest, TestGravityCompensationMissingParameters)
31
31
*/
32
32
}
33
33
34
- TEST_F (GravityCompensationTest, TestGravityCompensationInvalidParameters )
34
+ TEST_F (GravityCompensationTest, TestGravityCompensationParameters )
35
35
{
36
36
std::shared_ptr<filters::FilterBase<geometry_msgs::msg::WrenchStamped>> filter_ =
37
37
std::make_shared<control_filters::GravityCompensation<geometry_msgs::msg::WrenchStamped>>();
@@ -49,7 +49,13 @@ TEST_F(GravityCompensationTest, TestGravityCompensationInvalidParameters)
49
49
node_->get_node_logging_interface (), node_->get_node_parameters_interface ()));
50
50
51
51
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
53
59
ASSERT_TRUE (filter_->configure (" " , " TestGravityCompensationFilter" ,
54
60
node_->get_node_logging_interface (), node_->get_node_parameters_interface ()));
55
61
}
0 commit comments