Skip to content

Commit 28711db

Browse files
authored
Proper controller update rate (ros-controls#1105)
1 parent ef56619 commit 28711db

File tree

4 files changed

+39
-25
lines changed

4 files changed

+39
-25
lines changed

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -122,6 +122,7 @@ class ControllerManager : public rclcpp::Node
122122
controller_spec.c = controller;
123123
controller_spec.info.name = controller_name;
124124
controller_spec.info.type = controller_type;
125+
controller_spec.next_update_cycle_time = std::make_shared<rclcpp::Time>(0);
125126
return add_controller_impl(controller_spec);
126127
}
127128

controller_manager/include/controller_manager/controller_spec.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#define CONTROLLER_MANAGER__CONTROLLER_SPEC_HPP_
2121

2222
#include <map>
23+
#include <memory>
2324
#include <string>
2425
#include <vector>
2526
#include "controller_interface/controller_interface.hpp"
@@ -37,6 +38,7 @@ struct ControllerSpec
3738
{
3839
hardware_interface::ControllerInfo info;
3940
controller_interface::ControllerInterfaceBaseSharedPtr c;
41+
std::shared_ptr<rclcpp::Time> next_update_cycle_time;
4042
};
4143

4244
} // namespace controller_manager

controller_manager/src/controller_manager.cpp

Lines changed: 24 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -565,6 +565,7 @@ controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::load_c
565565
controller_spec.c = controller;
566566
controller_spec.info.name = controller_name;
567567
controller_spec.info.type = controller_type;
568+
controller_spec.next_update_cycle_time = std::make_shared<rclcpp::Time>(0);
568569

569570
return add_controller_impl(controller_spec);
570571
}
@@ -740,16 +741,13 @@ controller_interface::return_type ControllerManager::configure_controller(
740741
}
741742
else if (controller_update_rate != 0 && cm_update_rate % controller_update_rate != 0)
742743
{
743-
// NOTE: The following computation is done to compute the approx controller update that can be
744-
// achieved w.r.t to the CM's update rate. This is done this way to take into account the
745-
// unsigned integer division.
746-
const auto act_ctrl_update_rate = cm_update_rate / (cm_update_rate / controller_update_rate);
747744
RCLCPP_WARN(
748745
get_logger(),
749-
"The controller : %s update rate : %d Hz is not a perfect divisor of the controller "
750-
"manager's update rate : %d Hz!. The controller will be updated with nearest divisor's "
751-
"update rate which is : %d Hz.",
752-
controller_name.c_str(), controller_update_rate, cm_update_rate, act_ctrl_update_rate);
746+
"The controller : %s update cycles won't be triggered at a constant period : %f sec, as the "
747+
"controller's update rate : %d Hz is not a perfect divisor of the controller manager's "
748+
"update rate : %d Hz!.",
749+
controller_name.c_str(), 1.0 / controller_update_rate, controller_update_rate,
750+
cm_update_rate);
753751
}
754752

755753
// CHAINABLE CONTROLLERS: get reference interfaces from chainable controllers
@@ -1458,6 +1456,8 @@ void ControllerManager::activate_controllers(
14581456
}
14591457
auto controller = found_it->c;
14601458
auto controller_name = found_it->info.name;
1459+
// reset the next update cycle time for newly activated controllers
1460+
*found_it->next_update_cycle_time = rclcpp::Time(0);
14611461

14621462
bool assignment_successful = true;
14631463
// assign command interfaces to the controller
@@ -2030,30 +2030,36 @@ controller_interface::return_type ControllerManager::update(
20302030
++update_loop_counter_;
20312031
update_loop_counter_ %= update_rate_;
20322032

2033-
for (auto loaded_controller : rt_controller_list)
2033+
for (const auto & loaded_controller : rt_controller_list)
20342034
{
20352035
// TODO(v-lopez) we could cache this information
20362036
// https://github.com/ros-controls/ros2_control/issues/153
20372037
if (!loaded_controller.c->is_async() && is_controller_active(*loaded_controller.c))
20382038
{
20392039
const auto controller_update_rate = loaded_controller.c->get_update_rate();
2040-
const auto controller_update_factor =
2041-
(controller_update_rate == 0) || (controller_update_rate >= update_rate_)
2042-
? 1u
2043-
: update_rate_ / controller_update_rate;
2040+
const bool run_controller_at_cm_rate =
2041+
(controller_update_rate == 0) || (controller_update_rate >= update_rate_);
2042+
const auto controller_period =
2043+
run_controller_at_cm_rate ? period
2044+
: rclcpp::Duration::from_seconds((1.0 / controller_update_rate));
2045+
2046+
bool controller_go = (time == rclcpp::Time(0)) ||
2047+
(time.seconds() >= loaded_controller.next_update_cycle_time->seconds());
20442048

2045-
bool controller_go = ((update_loop_counter_ % controller_update_factor) == 0);
20462049
RCLCPP_DEBUG(
20472050
get_logger(), "update_loop_counter: '%d ' controller_go: '%s ' controller_name: '%s '",
20482051
update_loop_counter_, controller_go ? "True" : "False",
20492052
loaded_controller.info.name.c_str());
20502053

20512054
if (controller_go)
20522055
{
2053-
auto controller_ret = loaded_controller.c->update(
2054-
time, (controller_update_factor != 1u)
2055-
? rclcpp::Duration::from_seconds(1.0 / controller_update_rate)
2056-
: period);
2056+
auto controller_ret = loaded_controller.c->update(time, controller_period);
2057+
2058+
if (*loaded_controller.next_update_cycle_time == rclcpp::Time(0))
2059+
{
2060+
*loaded_controller.next_update_cycle_time = time;
2061+
}
2062+
*loaded_controller.next_update_cycle_time += controller_period;
20572063

20582064
if (controller_ret != controller_interface::return_type::OK)
20592065
{

controller_manager/test/test_controller_manager.cpp

Lines changed: 12 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -423,23 +423,28 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
423423
EXPECT_EQ(test_controller->get_update_rate(), ctrl_update_rate);
424424
const auto cm_update_rate = cm_->get_update_rate();
425425
const auto controller_update_rate = test_controller->get_update_rate();
426-
const auto controller_factor = (cm_update_rate / controller_update_rate);
427-
const auto expected_controller_update_rate =
428-
static_cast<unsigned int>(std::round(cm_update_rate / static_cast<double>(controller_factor)));
429426

430427
const auto initial_counter = test_controller->internal_counter;
431-
for (size_t update_counter = 1; update_counter <= 10 * cm_update_rate; ++update_counter)
428+
rclcpp::Time time = rclcpp::Time(0);
429+
for (size_t update_counter = 0; update_counter <= 10 * cm_update_rate; ++update_counter)
432430
{
433431
EXPECT_EQ(
434432
controller_interface::return_type::OK,
435-
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
433+
cm_->update(time, rclcpp::Duration::from_seconds(0.01)));
436434

435+
time += rclcpp::Duration::from_seconds(0.01);
437436
if (update_counter % cm_update_rate == 0)
438437
{
439438
const auto no_of_secs_passed = update_counter / cm_update_rate;
440-
EXPECT_EQ(
439+
// NOTE: here EXPECT_NEAR is used because it is observed that in the first iteration of whole
440+
// cycle of cm_update_rate counts, there is one count missing, but in rest of the 9 cycles it
441+
// is clearly tracking, so adding 1 here won't affect the final count.
442+
// For instance, a controller with update rate 37 Hz, seems to have 36 in the first update
443+
// cycle and then on accumulating 37 on every other update cycle so at the end of the 10
444+
// cycles it will have 369 instead of 370.
445+
EXPECT_NEAR(
441446
test_controller->internal_counter - initial_counter,
442-
(expected_controller_update_rate * no_of_secs_passed));
447+
(controller_update_rate * no_of_secs_passed), 1);
443448
}
444449
}
445450
}

0 commit comments

Comments
 (0)