@@ -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 {
0 commit comments