Skip to content

Commit

Permalink
Apply suggestions from code review
Browse files Browse the repository at this point in the history
Co-authored-by: Bence Magyar <[email protected]>
  • Loading branch information
saikishor and bmagyar authored Oct 16, 2024
1 parent dae549c commit 17ec65f
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -424,7 +424,7 @@ class ControllerManager : public rclcpp::Node
const std::vector<ControllerSpec> & controllers, int strictness,
const ControllersListIterator controller_it);

/// The methood to check if the fallback controllers of the given controllers are in the right
/// Checks if the fallback controllers of the given controllers are in the right
/// state, so they can be activated immediately
/**
* \param[in] controllers is a list of controllers to activate.
Expand Down
5 changes: 3 additions & 2 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2409,10 +2409,11 @@ controller_interface::return_type ControllerManager::update(
}
if (!failed_controllers_list.empty())
{
const auto FALLBACK_STACK_MAX_SIZE = 500;
std::vector<std::string> active_controllers_using_interfaces(failed_controllers_list);
active_controllers_using_interfaces.reserve(500);
active_controllers_using_interfaces.reserve(FALLBACK_STACK_MAX_SIZE);
std::vector<std::string> cumulative_fallback_controllers;
cumulative_fallback_controllers.reserve(500);
cumulative_fallback_controllers.reserve(FALLBACK_STACK_MAX_SIZE);

for (const auto & failed_ctrl : failed_controllers_list)
{
Expand Down

0 comments on commit 17ec65f

Please sign in to comment.