Skip to content

Commit

Permalink
remove the AsyncControllerThread integration to replace it with Async…
Browse files Browse the repository at this point in the history
…FunctionHandler
  • Loading branch information
saikishor committed May 17, 2024
1 parent bee14fe commit 1984168
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 137 deletions.
111 changes: 0 additions & 111 deletions controller_interface/include/controller_interface/async_controller.hpp

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
#include <utility>
#include <vector>

#include "controller_interface/async_controller.hpp"
#include "controller_interface/chainable_controller_interface.hpp"
#include "controller_interface/controller_interface.hpp"
#include "controller_interface/controller_interface_base.hpp"
Expand Down Expand Up @@ -572,9 +571,6 @@ class ControllerManager : public rclcpp::Node
};

SwitchParams switch_params_;

std::unordered_map<std::string, std::unique_ptr<controller_interface::AsyncControllerThread>>
async_controller_threads_;
};

} // namespace controller_manager
Expand Down
22 changes: 0 additions & 22 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -555,13 +555,6 @@ controller_interface::return_type ControllerManager::unload_controller(
controller_name.c_str());
return controller_interface::return_type::ERROR;
}
if (controller.c->is_async())
{
RCLCPP_DEBUG(
get_logger(), "Removing controller '%s' from the list of async controllers",
controller_name.c_str());
async_controller_threads_.erase(controller_name);
}

RCLCPP_DEBUG(get_logger(), "Cleanup controller");
controller_chain_spec_cleanup(controller_chain_spec_, controller_name);
Expand Down Expand Up @@ -703,14 +696,6 @@ controller_interface::return_type ControllerManager::configure_controller(
return controller_interface::return_type::ERROR;
}

// ASYNCHRONOUS CONTROLLERS: Start background thread for update
if (controller->is_async())
{
async_controller_threads_.emplace(
controller_name,
std::make_unique<controller_interface::AsyncControllerThread>(controller, update_rate_));
}

const auto controller_update_rate = controller->get_update_rate();
const auto cm_update_rate = get_update_rate();
if (controller_update_rate > cm_update_rate)
Expand Down Expand Up @@ -1632,11 +1617,6 @@ void ControllerManager::activate_controllers(
{
resource_manager_->make_controller_reference_interfaces_available(controller_name);
}

if (controller->is_async())
{
async_controller_threads_.at(controller_name)->activate();
}
}
}

Expand Down Expand Up @@ -2333,8 +2313,6 @@ unsigned int ControllerManager::get_update_rate() const { return update_rate_; }

void ControllerManager::shutdown_async_controllers_and_components()
{
async_controller_threads_.erase(
async_controller_threads_.begin(), async_controller_threads_.end());
resource_manager_->shutdown_async_components();
}

Expand Down

0 comments on commit 1984168

Please sign in to comment.