Skip to content

Commit

Permalink
remove unnecessary parts
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Sep 24, 2024
1 parent cabe347 commit 57c4f56
Showing 1 changed file with 0 additions and 29 deletions.
29 changes: 0 additions & 29 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2197,8 +2197,6 @@ void ControllerManager::read(const rclcpp::Time & time, const rclcpp::Duration &
std::vector<std::string> stop_request = {};
std::string failed_hardware_string;
failed_hardware_string.reserve(500);
std::vector<std::string> failed_controller_interfaces;
failed_controller_interfaces.reserve(500);
// Determine controllers to stop
for (const auto & hardware_name : failed_hardware_names)
{
Expand All @@ -2223,21 +2221,8 @@ void ControllerManager::read(const rclcpp::Time & time, const rclcpp::Duration &
"Deactivating following controllers as their hardware components read cycle resulted in an "
"error: [ %s]",
stop_request_string.c_str());

std::vector<ControllerSpec> & rt_controller_list =
rt_controllers_wrapper_.update_and_get_used_by_rt_list();
get_controller_list_command_interfaces(
stop_request, rt_controller_list, *resource_manager_, failed_controller_interfaces);
if (!failed_controller_interfaces.empty())
{
if (!(resource_manager_->prepare_command_mode_switch({}, failed_controller_interfaces) &&
resource_manager_->perform_command_mode_switch({}, failed_controller_interfaces)))
{
RCLCPP_ERROR(
get_logger(),
"Error while attempting mode switch when deactivating controllers in read cycle!");
}
}
deactivate_controllers(rt_controller_list, stop_request);
// TODO(destogl): do auto-start of broadcasters
}
Expand Down Expand Up @@ -2408,8 +2393,6 @@ void ControllerManager::write(const rclcpp::Time & time, const rclcpp::Duration
std::vector<std::string> stop_request = {};
std::string failed_hardware_string;
failed_hardware_string.reserve(500);
std::vector<std::string> failed_controller_interfaces;
failed_controller_interfaces.reserve(500);
// Determine controllers to stop
for (const auto & hardware_name : failed_hardware_names)
{
Expand Down Expand Up @@ -2437,18 +2420,6 @@ void ControllerManager::write(const rclcpp::Time & time, const rclcpp::Duration
stop_request_string.c_str());
std::vector<ControllerSpec> & rt_controller_list =
rt_controllers_wrapper_.update_and_get_used_by_rt_list();
get_controller_list_command_interfaces(
stop_request, rt_controller_list, *resource_manager_, failed_controller_interfaces);
if (!failed_controller_interfaces.empty())
{
if (!(resource_manager_->prepare_command_mode_switch({}, failed_controller_interfaces) &&
resource_manager_->perform_command_mode_switch({}, failed_controller_interfaces)))
{
RCLCPP_ERROR(
get_logger(),
"Error while attempting mode switch when deactivating controllers in write cycle!");
}
}
deactivate_controllers(rt_controller_list, stop_request);
// TODO(destogl): do auto-start of broadcasters
}
Expand Down

0 comments on commit 57c4f56

Please sign in to comment.