Skip to content

Commit d39ddcd

Browse files
authored
Fix equal and higher controller update rate (#1070)
1 parent 185fbea commit d39ddcd

File tree

3 files changed

+131
-9
lines changed

3 files changed

+131
-9
lines changed

controller_manager/src/controller_manager.cpp

Lines changed: 15 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -610,6 +610,18 @@ controller_interface::return_type ControllerManager::configure_controller(
610610
controller_name, std::make_unique<ControllerThreadWrapper>(controller, update_rate_));
611611
}
612612

613+
const auto controller_update_rate = controller->get_update_rate();
614+
const auto cm_update_rate = get_update_rate();
615+
if (controller_update_rate > cm_update_rate)
616+
{
617+
RCLCPP_WARN(
618+
get_logger(),
619+
"The controller : %s update rate : %d Hz should be less than or equal to controller "
620+
"manager's update rate : %d Hz!. The controller will be updated at controller_manager's "
621+
"update rate.",
622+
controller_name.c_str(), controller_update_rate, cm_update_rate);
623+
}
624+
613625
// CHAINABLE CONTROLLERS: get reference interfaces from chainable controllers
614626
if (controller->is_chainable())
615627
{
@@ -1873,8 +1885,9 @@ controller_interface::return_type ControllerManager::update(
18731885
{
18741886
const auto controller_update_rate = loaded_controller.c->get_update_rate();
18751887

1876-
bool controller_go =
1877-
controller_update_rate == 0 || ((update_loop_counter_ % controller_update_rate) == 0);
1888+
bool controller_go = controller_update_rate == 0 ||
1889+
((update_loop_counter_ % controller_update_rate) == 0) ||
1890+
(controller_update_rate >= update_rate_);
18781891
RCLCPP_DEBUG(
18791892
get_logger(), "update_loop_counter: '%d ' controller_go: '%s ' controller_name: '%s '",
18801893
update_loop_counter_, controller_go ? "True" : "False",

controller_manager/test/test_controller/test_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ class TestController : public controller_interface::ControllerInterface
6565
CONTROLLER_MANAGER_PUBLIC
6666
void set_state_interface_configuration(const controller_interface::InterfaceConfiguration & cfg);
6767

68-
size_t internal_counter = 0;
68+
unsigned int internal_counter = 0;
6969
bool simulate_cleanup_failure = false;
7070
// Variable where we store when cleanup was called, pointer because the controller
7171
// is usually destroyed after cleanup

controller_manager/test/test_controller_manager.cpp

Lines changed: 115 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include <gtest/gtest.h>
15+
#include <gmock/gmock.h>
1616
#include <memory>
1717
#include <string>
1818
#include <utility>
@@ -27,13 +27,13 @@
2727
using ::testing::_;
2828
using ::testing::Return;
2929

30-
class TestControllerManager
30+
class TestControllerManagerWithStrictness
3131
: public ControllerManagerFixture<controller_manager::ControllerManager>,
3232
public testing::WithParamInterface<Strictness>
3333
{
3434
};
3535

36-
TEST_P(TestControllerManager, controller_lifecycle)
36+
TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
3737
{
3838
const auto test_param = GetParam();
3939
auto test_controller = std::make_shared<test_controller::TestController>();
@@ -159,7 +159,7 @@ TEST_P(TestControllerManager, controller_lifecycle)
159159
controller_interface::return_type::OK,
160160
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
161161
EXPECT_GE(test_controller->internal_counter, 1u);
162-
auto last_internal_counter = test_controller->internal_counter;
162+
size_t last_internal_counter = test_controller->internal_counter;
163163

164164
// Stop controller, will take effect at the end of the update function
165165
start_controllers = {};
@@ -196,7 +196,7 @@ TEST_P(TestControllerManager, controller_lifecycle)
196196
EXPECT_EQ(1, test_controller.use_count());
197197
}
198198

199-
TEST_P(TestControllerManager, per_controller_update_rate)
199+
TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)
200200
{
201201
auto strictness = GetParam().strictness;
202202
auto test_controller = std::make_shared<test_controller::TestController>();
@@ -254,4 +254,113 @@ TEST_P(TestControllerManager, per_controller_update_rate)
254254
}
255255

256256
INSTANTIATE_TEST_SUITE_P(
257-
test_strict_best_effort, TestControllerManager, testing::Values(strict, best_effort));
257+
test_strict_best_effort, TestControllerManagerWithStrictness,
258+
testing::Values(strict, best_effort));
259+
260+
class TestControllerManagerWithUpdateRates
261+
: public ControllerManagerFixture<controller_manager::ControllerManager>,
262+
public testing::WithParamInterface<unsigned int>
263+
{
264+
};
265+
266+
TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_update_rate)
267+
{
268+
const auto strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
269+
const unsigned int ctrl_update_rate = GetParam();
270+
auto test_controller = std::make_shared<test_controller::TestController>();
271+
272+
auto last_internal_counter = 0u;
273+
RCLCPP_INFO(
274+
rclcpp::get_logger("test_controller_manager"), "Testing update rate : %u Hz", ctrl_update_rate);
275+
{
276+
ControllerManagerRunner cm_runner(this);
277+
cm_->add_controller(
278+
test_controller, test_controller::TEST_CONTROLLER_NAME,
279+
test_controller::TEST_CONTROLLER_CLASS_NAME);
280+
}
281+
EXPECT_EQ(1u, cm_->get_loaded_controllers().size());
282+
EXPECT_EQ(2, test_controller.use_count());
283+
EXPECT_EQ(
284+
controller_interface::return_type::OK,
285+
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
286+
EXPECT_EQ(last_internal_counter, test_controller->internal_counter)
287+
<< "Update should not reach an unconfigured controller";
288+
289+
EXPECT_EQ(
290+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id());
291+
292+
rclcpp::Parameter update_rate_parameter("update_rate", static_cast<int>(ctrl_update_rate));
293+
test_controller->get_node()->set_parameter(update_rate_parameter);
294+
// configure controller
295+
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
296+
EXPECT_EQ(
297+
controller_interface::return_type::OK,
298+
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
299+
EXPECT_EQ(last_internal_counter, test_controller->internal_counter)
300+
<< "Controller is not started";
301+
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id());
302+
303+
// Start controller, will take effect at the end of the update function
304+
std::vector<std::string> start_controllers = {test_controller::TEST_CONTROLLER_NAME};
305+
std::vector<std::string> stop_controllers = {};
306+
auto switch_future = std::async(
307+
std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
308+
start_controllers, stop_controllers, strictness, true, rclcpp::Duration(0, 0));
309+
310+
ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100)))
311+
<< "switch_controller should be blocking until next update cycle";
312+
313+
EXPECT_EQ(
314+
controller_interface::return_type::OK,
315+
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
316+
EXPECT_EQ(last_internal_counter, test_controller->internal_counter)
317+
<< "Controller is started at the end of update";
318+
{
319+
ControllerManagerRunner cm_runner(this);
320+
EXPECT_EQ(controller_interface::return_type::OK, switch_future.get());
321+
}
322+
323+
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state().id());
324+
325+
const auto pre_internal_counter = test_controller->internal_counter;
326+
rclcpp::Rate loop_rate(cm_->get_update_rate());
327+
for (size_t i = 0; i < 2 * cm_->get_update_rate(); i++)
328+
{
329+
EXPECT_EQ(
330+
controller_interface::return_type::OK,
331+
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
332+
loop_rate.sleep();
333+
}
334+
// if we do 2 times of the controller_manager update rate, the internal counter should be
335+
// similarly incremented
336+
EXPECT_EQ(test_controller->internal_counter, pre_internal_counter + (2 * cm_->get_update_rate()));
337+
EXPECT_EQ(test_controller->get_update_rate(), ctrl_update_rate);
338+
339+
auto deactivate_future = std::async(
340+
std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
341+
stop_controllers, start_controllers, strictness, true, rclcpp::Duration(0, 0));
342+
343+
ASSERT_EQ(std::future_status::timeout, deactivate_future.wait_for(std::chrono::milliseconds(100)))
344+
<< "switch_controller should be blocking until next update cycle";
345+
346+
EXPECT_EQ(
347+
controller_interface::return_type::OK,
348+
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)))
349+
<< "Controller is stopped at the end of update, so it should have done one more update";
350+
{
351+
ControllerManagerRunner cm_runner(this);
352+
EXPECT_EQ(controller_interface::return_type::OK, deactivate_future.get());
353+
}
354+
auto unload_future = std::async(
355+
std::launch::async, &controller_manager::ControllerManager::unload_controller, cm_,
356+
test_controller::TEST_CONTROLLER_NAME);
357+
ASSERT_EQ(std::future_status::timeout, unload_future.wait_for(std::chrono::milliseconds(100)))
358+
<< "unload_controller should be blocking until next update cycle";
359+
ControllerManagerRunner cm_runner(this);
360+
EXPECT_EQ(controller_interface::return_type::OK, unload_future.get());
361+
last_internal_counter = test_controller->internal_counter;
362+
}
363+
364+
INSTANTIATE_TEST_SUITE_P(
365+
per_controller_equal_and_higher_update_rate, TestControllerManagerWithUpdateRates,
366+
testing::Values(100, 232, 400));

0 commit comments

Comments
 (0)