Skip to content

Commit 2cbe470

Browse files
authored
Working async controllers and components [not synchronized] (#1041)
1 parent 607755e commit 2cbe470

File tree

7 files changed

+176
-78
lines changed

7 files changed

+176
-78
lines changed
Lines changed: 111 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,111 @@
1+
// Copyright 2024 ros2_control development team
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef CONTROLLER_INTERFACE__ASYNC_CONTROLLER_HPP_
16+
#define CONTROLLER_INTERFACE__ASYNC_CONTROLLER_HPP_
17+
18+
#include <atomic>
19+
#include <memory>
20+
#include <thread>
21+
22+
#include "controller_interface_base.hpp"
23+
#include "lifecycle_msgs/msg/state.hpp"
24+
25+
namespace controller_interface
26+
{
27+
28+
class AsyncControllerThread
29+
{
30+
public:
31+
/// Constructor for the AsyncControllerThread object.
32+
/**
33+
*
34+
* \param[in] controller shared pointer to a controller.
35+
* \param[in] cm_update_rate the controller manager's update rate.
36+
*/
37+
AsyncControllerThread(
38+
std::shared_ptr<controller_interface::ControllerInterfaceBase> & controller, int cm_update_rate)
39+
: terminated_(false), controller_(controller), thread_{}, cm_update_rate_(cm_update_rate)
40+
{
41+
}
42+
43+
AsyncControllerThread(const AsyncControllerThread & t) = delete;
44+
AsyncControllerThread(AsyncControllerThread && t) = delete;
45+
46+
// Destructor, called when the component is erased from its map.
47+
~AsyncControllerThread()
48+
{
49+
terminated_.store(true, std::memory_order_seq_cst);
50+
if (thread_.joinable())
51+
{
52+
thread_.join();
53+
}
54+
}
55+
56+
/// Creates the controller's thread.
57+
/**
58+
* Called when the controller is activated.
59+
*
60+
*/
61+
void activate()
62+
{
63+
thread_ = std::thread(&AsyncControllerThread::controller_update_callback, this);
64+
}
65+
66+
/// Periodically execute the controller's update method.
67+
/**
68+
* Callback of the async controller's thread.
69+
* **Not synchronized with the controller manager's write and read currently**
70+
*
71+
*/
72+
void controller_update_callback()
73+
{
74+
using TimePoint = std::chrono::system_clock::time_point;
75+
unsigned int used_update_rate =
76+
controller_->get_update_rate() == 0 ? cm_update_rate_ : controller_->get_update_rate();
77+
78+
auto previous_time = controller_->get_node()->now();
79+
while (!terminated_.load(std::memory_order_relaxed))
80+
{
81+
auto const period = std::chrono::nanoseconds(1'000'000'000 / used_update_rate);
82+
TimePoint next_iteration_time =
83+
TimePoint(std::chrono::nanoseconds(controller_->get_node()->now().nanoseconds()));
84+
85+
if (controller_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
86+
{
87+
auto const current_time = controller_->get_node()->now();
88+
auto const measured_period = current_time - previous_time;
89+
previous_time = current_time;
90+
controller_->update(
91+
controller_->get_node()->now(),
92+
(controller_->get_update_rate() != cm_update_rate_ && controller_->get_update_rate() != 0)
93+
? rclcpp::Duration::from_seconds(1.0 / controller_->get_update_rate())
94+
: measured_period);
95+
}
96+
97+
next_iteration_time += period;
98+
std::this_thread::sleep_until(next_iteration_time);
99+
}
100+
}
101+
102+
private:
103+
std::atomic<bool> terminated_;
104+
std::shared_ptr<controller_interface::ControllerInterfaceBase> controller_;
105+
std::thread thread_;
106+
unsigned int cm_update_rate_;
107+
};
108+
109+
} // namespace controller_interface
110+
111+
#endif // CONTROLLER_INTERFACE__ASYNC_CONTROLLER_HPP_

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 11 additions & 59 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include <utility>
2424
#include <vector>
2525

26+
#include "controller_interface/async_controller.hpp"
2627
#include "controller_interface/chainable_controller_interface.hpp"
2728
#include "controller_interface/controller_interface.hpp"
2829
#include "controller_interface/controller_interface_base.hpp"
@@ -196,6 +197,15 @@ class ControllerManager : public rclcpp::Node
196197
CONTROLLER_MANAGER_PUBLIC
197198
unsigned int get_update_rate() const;
198199

200+
/// Deletes all async controllers and components.
201+
/**
202+
* Needed to join the threads immediately after the control loop is ended
203+
* to avoid unnecessary iterations. Otherwise
204+
* the threads will be joined only when the controller manager gets destroyed.
205+
*/
206+
CONTROLLER_MANAGER_PUBLIC
207+
void shutdown_async_controllers_and_components();
208+
199209
protected:
200210
CONTROLLER_MANAGER_PUBLIC
201211
void init_services();
@@ -563,65 +573,7 @@ class ControllerManager : public rclcpp::Node
563573

564574
SwitchParams switch_params_;
565575

566-
class ControllerThreadWrapper
567-
{
568-
public:
569-
ControllerThreadWrapper(
570-
std::shared_ptr<controller_interface::ControllerInterfaceBase> & controller,
571-
int cm_update_rate)
572-
: terminated_(false), controller_(controller), thread_{}, cm_update_rate_(cm_update_rate)
573-
{
574-
}
575-
576-
ControllerThreadWrapper(const ControllerThreadWrapper & t) = delete;
577-
ControllerThreadWrapper(ControllerThreadWrapper && t) = default;
578-
~ControllerThreadWrapper()
579-
{
580-
terminated_.store(true, std::memory_order_seq_cst);
581-
if (thread_.joinable())
582-
{
583-
thread_.join();
584-
}
585-
}
586-
587-
void activate()
588-
{
589-
thread_ = std::thread(&ControllerThreadWrapper::call_controller_update, this);
590-
}
591-
592-
void call_controller_update()
593-
{
594-
using TimePoint = std::chrono::system_clock::time_point;
595-
unsigned int used_update_rate =
596-
controller_->get_update_rate() == 0
597-
? cm_update_rate_
598-
: controller_
599-
->get_update_rate(); // determines if the controller's or CM's update rate is used
600-
601-
while (!terminated_.load(std::memory_order_relaxed))
602-
{
603-
auto const period = std::chrono::nanoseconds(1'000'000'000 / used_update_rate);
604-
TimePoint next_iteration_time =
605-
TimePoint(std::chrono::nanoseconds(controller_->get_node()->now().nanoseconds()));
606-
607-
if (controller_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
608-
{
609-
// critical section, not implemented yet
610-
}
611-
612-
next_iteration_time += period;
613-
std::this_thread::sleep_until(next_iteration_time);
614-
}
615-
}
616-
617-
private:
618-
std::atomic<bool> terminated_;
619-
std::shared_ptr<controller_interface::ControllerInterfaceBase> controller_;
620-
std::thread thread_;
621-
unsigned int cm_update_rate_;
622-
};
623-
624-
std::unordered_map<std::string, std::unique_ptr<ControllerThreadWrapper>>
576+
std::unordered_map<std::string, std::unique_ptr<controller_interface::AsyncControllerThread>>
625577
async_controller_threads_;
626578
};
627579

controller_manager/src/controller_manager.cpp

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -707,7 +707,8 @@ controller_interface::return_type ControllerManager::configure_controller(
707707
if (controller->is_async())
708708
{
709709
async_controller_threads_.emplace(
710-
controller_name, std::make_unique<ControllerThreadWrapper>(controller, update_rate_));
710+
controller_name,
711+
std::make_unique<controller_interface::AsyncControllerThread>(controller, update_rate_));
711712
}
712713

713714
const auto controller_update_rate = controller->get_update_rate();
@@ -2317,6 +2318,13 @@ std::pair<std::string, std::string> ControllerManager::split_command_interface(
23172318

23182319
unsigned int ControllerManager::get_update_rate() const { return update_rate_; }
23192320

2321+
void ControllerManager::shutdown_async_controllers_and_components()
2322+
{
2323+
async_controller_threads_.erase(
2324+
async_controller_threads_.begin(), async_controller_threads_.end());
2325+
resource_manager_->shutdown_async_components();
2326+
}
2327+
23202328
void ControllerManager::propagate_deactivation_of_chained_mode(
23212329
const std::vector<ControllerSpec> & controllers)
23222330
{

controller_manager/src/ros2_control_node.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -83,6 +83,8 @@ int main(int argc, char ** argv)
8383
next_iteration_time += period;
8484
std::this_thread::sleep_until(next_iteration_time);
8585
}
86+
87+
cm->shutdown_async_controllers_and_components();
8688
});
8789

8890
executor->add_node(cm);

hardware_interface/include/hardware_interface/async_components.hpp

Lines changed: 27 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include <atomic>
1919
#include <thread>
20+
#include <type_traits>
2021
#include <variant>
2122

2223
#include "hardware_interface/actuator.hpp"
@@ -34,29 +35,23 @@ class AsyncComponentThread
3435
{
3536
public:
3637
explicit AsyncComponentThread(
37-
Actuator * component, unsigned int update_rate,
38+
unsigned int update_rate,
3839
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
39-
: hardware_component_(component), cm_update_rate_(update_rate), clock_interface_(clock_interface)
40+
: cm_update_rate_(update_rate), clock_interface_(clock_interface)
4041
{
4142
}
4243

43-
explicit AsyncComponentThread(
44-
System * component, unsigned int update_rate,
45-
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
46-
: hardware_component_(component), cm_update_rate_(update_rate), clock_interface_(clock_interface)
47-
{
48-
}
49-
50-
explicit AsyncComponentThread(
51-
Sensor * component, unsigned int update_rate,
52-
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
53-
: hardware_component_(component), cm_update_rate_(update_rate), clock_interface_(clock_interface)
44+
// Fills the internal variant with the desired component.
45+
template <typename T>
46+
void register_component(T * component)
5447
{
48+
hardware_component_ = component;
5549
}
5650

5751
AsyncComponentThread(const AsyncComponentThread & t) = delete;
58-
AsyncComponentThread(AsyncComponentThread && t) = default;
52+
AsyncComponentThread(AsyncComponentThread && t) = delete;
5953

54+
// Destructor, called when the component is erased from its map.
6055
~AsyncComponentThread()
6156
{
6257
terminated_.store(true, std::memory_order_seq_cst);
@@ -65,9 +60,19 @@ class AsyncComponentThread
6560
write_and_read_.join();
6661
}
6762
}
68-
63+
/// Creates the component's thread.
64+
/**
65+
* Called when the component is activated.
66+
*
67+
*/
6968
void activate() { write_and_read_ = std::thread(&AsyncComponentThread::write_and_read, this); }
7069

70+
/// Periodically execute the component's write and read methods.
71+
/**
72+
* Callback of the async component's thread.
73+
* **Not synchronized with the controller manager's update currently**
74+
*
75+
*/
7176
void write_and_read()
7277
{
7378
using TimePoint = std::chrono::system_clock::time_point;
@@ -88,8 +93,12 @@ class AsyncComponentThread
8893
auto measured_period = current_time - previous_time;
8994
previous_time = current_time;
9095

91-
// write
92-
// read
96+
if (!first_iteration)
97+
{
98+
component->write(clock_interface_->get_clock()->now(), measured_period);
99+
}
100+
component->read(clock_interface_->get_clock()->now(), measured_period);
101+
first_iteration = false;
93102
}
94103
next_iteration_time += period;
95104
std::this_thread::sleep_until(next_iteration_time);
@@ -104,6 +113,7 @@ class AsyncComponentThread
104113
std::thread write_and_read_{};
105114

106115
unsigned int cm_update_rate_;
116+
bool first_iteration = true;
107117
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
108118
};
109119

hardware_interface/include/hardware_interface/resource_manager.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -376,6 +376,12 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
376376
return_type set_component_state(
377377
const std::string & component_name, rclcpp_lifecycle::State & target_state);
378378

379+
/// Deletes all async components from the resource storage
380+
/**
381+
* Needed to join the threads immediately after the control loop is ended.
382+
*/
383+
void shutdown_async_components();
384+
379385
/// Reads all loaded hardware components.
380386
/**
381387
* Reads from all active hardware components.

hardware_interface/src/resource_manager.cpp

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -206,7 +206,9 @@ class ResourceStorage
206206
{
207207
async_component_threads_.emplace(
208208
std::piecewise_construct, std::forward_as_tuple(hardware.get_name()),
209-
std::forward_as_tuple(&hardware, cm_update_rate_, clock_interface_));
209+
std::forward_as_tuple(cm_update_rate_, clock_interface_));
210+
211+
async_component_threads_.at(hardware.get_name()).register_component(&hardware);
210212
}
211213
}
212214
return result;
@@ -1324,6 +1326,13 @@ return_type ResourceManager::set_component_state(
13241326
return result;
13251327
}
13261328

1329+
void ResourceManager::shutdown_async_components()
1330+
{
1331+
resource_storage_->async_component_threads_.erase(
1332+
resource_storage_->async_component_threads_.begin(),
1333+
resource_storage_->async_component_threads_.end());
1334+
}
1335+
13271336
// CM API: Called in "update"-thread
13281337
HardwareReadWriteStatus ResourceManager::read(
13291338
const rclcpp::Time & time, const rclcpp::Duration & period)

0 commit comments

Comments
 (0)