Skip to content

Commit af8ab04

Browse files
committed
Create poc for distributed control
1 parent ecc2218 commit af8ab04

File tree

23 files changed

+1607
-116
lines changed

23 files changed

+1607
-116
lines changed

controller_interface/test/test_force_torque_sensor.cpp

Lines changed: 32 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -47,20 +47,20 @@ TEST_F(ForceTorqueSensorTest, validate_all_with_default_names)
4747
std::vector<std::string> interface_names = force_torque_sensor_->get_state_interface_names();
4848

4949
// assign values to force
50-
hardware_interface::StateInterface force_x{
51-
sensor_name_, fts_interface_names_[0], &force_values_[0]};
52-
hardware_interface::StateInterface force_y{
53-
sensor_name_, fts_interface_names_[1], &force_values_[1]};
54-
hardware_interface::StateInterface force_z{
55-
sensor_name_, fts_interface_names_[2], &force_values_[2]};
50+
auto force_x = std::make_shared<hardware_interface::StateInterface>(
51+
sensor_name_, fts_interface_names_[0], &force_values_[0]);
52+
auto force_y = std::make_shared<hardware_interface::StateInterface>(
53+
sensor_name_, fts_interface_names_[1], &force_values_[1]);
54+
auto force_z = std::make_shared<hardware_interface::StateInterface>(
55+
sensor_name_, fts_interface_names_[2], &force_values_[2]);
5656

5757
// assign values to torque
58-
hardware_interface::StateInterface torque_x{
59-
sensor_name_, fts_interface_names_[3], &torque_values_[0]};
60-
hardware_interface::StateInterface torque_y{
61-
sensor_name_, fts_interface_names_[4], &torque_values_[1]};
62-
hardware_interface::StateInterface torque_z{
63-
sensor_name_, fts_interface_names_[5], &torque_values_[2]};
58+
auto torque_x = std::make_shared<hardware_interface::StateInterface>(
59+
sensor_name_, fts_interface_names_[3], &torque_values_[0]);
60+
auto torque_y = std::make_shared<hardware_interface::StateInterface>(
61+
sensor_name_, fts_interface_names_[4], &torque_values_[1]);
62+
auto torque_z = std::make_shared<hardware_interface::StateInterface>(
63+
sensor_name_, fts_interface_names_[5], &torque_values_[2]);
6464

6565
// create local state interface vector
6666
std::vector<hardware_interface::LoanedStateInterface> temp_state_interfaces;
@@ -131,16 +131,16 @@ TEST_F(ForceTorqueSensorTest, validate_all_with_custom_names)
131131
std::vector<std::string> interface_names = force_torque_sensor_->get_state_interface_names();
132132

133133
// assign values to force.x and force.z
134-
hardware_interface::StateInterface force_x{
135-
sensor_name_, fts_interface_names_[0], &force_values_[0]};
136-
hardware_interface::StateInterface force_z{
137-
sensor_name_, fts_interface_names_[2], &force_values_[2]};
134+
auto force_x = std::make_shared<hardware_interface::StateInterface>(
135+
sensor_name_, fts_interface_names_[0], &force_values_[0]);
136+
auto force_z = std::make_shared<hardware_interface::StateInterface>(
137+
sensor_name_, fts_interface_names_[2], &force_values_[2]);
138138

139139
// assign values to torque.y and torque.z
140-
hardware_interface::StateInterface torque_y{
141-
sensor_name_, fts_interface_names_[4], &torque_values_[1]};
142-
hardware_interface::StateInterface torque_z{
143-
sensor_name_, fts_interface_names_[5], &torque_values_[2]};
140+
auto torque_y = std::make_shared<hardware_interface::StateInterface>(
141+
sensor_name_, fts_interface_names_[4], &torque_values_[1]);
142+
auto torque_z = std::make_shared<hardware_interface::StateInterface>(
143+
sensor_name_, fts_interface_names_[5], &torque_values_[2]);
144144

145145
// create local state interface vector
146146
std::vector<hardware_interface::LoanedStateInterface> temp_state_interfaces;
@@ -213,20 +213,20 @@ TEST_F(ForceTorqueSensorTest, validate_all_custom_names)
213213
ASSERT_EQ(force_torque_sensor_->interface_names_[5], sensor_name_ + "/" + "torque.z");
214214

215215
// assign values to force
216-
hardware_interface::StateInterface force_x{
217-
sensor_name_, fts_interface_names_[0], &force_values_[0]};
218-
hardware_interface::StateInterface force_y{
219-
sensor_name_, fts_interface_names_[1], &force_values_[1]};
220-
hardware_interface::StateInterface force_z{
221-
sensor_name_, fts_interface_names_[2], &force_values_[2]};
216+
auto force_x = std::make_shared<hardware_interface::StateInterface>(
217+
sensor_name_, fts_interface_names_[0], &force_values_[0]);
218+
auto force_y = std::make_shared<hardware_interface::StateInterface>(
219+
sensor_name_, fts_interface_names_[1], &force_values_[1]);
220+
auto force_z = std::make_shared<hardware_interface::StateInterface>(
221+
sensor_name_, fts_interface_names_[2], &force_values_[2]);
222222

223223
// assign values to torque
224-
hardware_interface::StateInterface torque_x{
225-
sensor_name_, fts_interface_names_[3], &torque_values_[0]};
226-
hardware_interface::StateInterface torque_y{
227-
sensor_name_, fts_interface_names_[4], &torque_values_[1]};
228-
hardware_interface::StateInterface torque_z{
229-
sensor_name_, fts_interface_names_[5], &torque_values_[2]};
224+
auto torque_x = std::make_shared<hardware_interface::StateInterface>(
225+
sensor_name_, fts_interface_names_[3], &torque_values_[0]);
226+
auto torque_y = std::make_shared<hardware_interface::StateInterface>(
227+
sensor_name_, fts_interface_names_[4], &torque_values_[1]);
228+
auto torque_z = std::make_shared<hardware_interface::StateInterface>(
229+
sensor_name_, fts_interface_names_[5], &torque_values_[2]);
230230

231231
// create local state interface vector
232232
std::vector<hardware_interface::LoanedStateInterface> temp_state_interfaces;

controller_interface/test/test_imu_sensor.cpp

Lines changed: 20 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -46,30 +46,30 @@ TEST_F(IMUSensorTest, validate_all)
4646
std::vector<std::string> interface_names = imu_sensor_->get_state_interface_names();
4747

4848
// assign values to orientation
49-
hardware_interface::StateInterface orientation_x{
50-
sensor_name_, imu_interface_names_[0], &orientation_values_[0]};
51-
hardware_interface::StateInterface orientation_y{
52-
sensor_name_, imu_interface_names_[1], &orientation_values_[1]};
53-
hardware_interface::StateInterface orientation_z{
54-
sensor_name_, imu_interface_names_[2], &orientation_values_[2]};
55-
hardware_interface::StateInterface orientation_w{
56-
sensor_name_, imu_interface_names_[3], &orientation_values_[4]};
49+
auto orientation_x = std::make_shared<hardware_interface::StateInterface>(
50+
sensor_name_, imu_interface_names_[0], &orientation_values_[0]);
51+
auto orientation_y = std::make_shared<hardware_interface::StateInterface>(
52+
sensor_name_, imu_interface_names_[1], &orientation_values_[1]);
53+
auto orientation_z = std::make_shared<hardware_interface::StateInterface>(
54+
sensor_name_, imu_interface_names_[2], &orientation_values_[2]);
55+
auto orientation_w = std::make_shared<hardware_interface::StateInterface>(
56+
sensor_name_, imu_interface_names_[3], &orientation_values_[4]);
5757

5858
// assign values to angular velocity
59-
hardware_interface::StateInterface angular_velocity_x{
60-
sensor_name_, imu_interface_names_[4], &angular_velocity_values_[0]};
61-
hardware_interface::StateInterface angular_velocity_y{
62-
sensor_name_, imu_interface_names_[5], &angular_velocity_values_[1]};
63-
hardware_interface::StateInterface angular_velocity_z{
64-
sensor_name_, imu_interface_names_[6], &angular_velocity_values_[2]};
59+
auto angular_velocity_x = std::make_shared<hardware_interface::StateInterface>(
60+
sensor_name_, imu_interface_names_[4], &angular_velocity_values_[0]);
61+
auto angular_velocity_y = std::make_shared<hardware_interface::StateInterface>(
62+
sensor_name_, imu_interface_names_[5], &angular_velocity_values_[1]);
63+
auto angular_velocity_z = std::make_shared<hardware_interface::StateInterface>(
64+
sensor_name_, imu_interface_names_[6], &angular_velocity_values_[2]);
6565

6666
// assign values to linear acceleration
67-
hardware_interface::StateInterface linear_acceleration_x{
68-
sensor_name_, imu_interface_names_[7], &linear_acceleration_values_[0]};
69-
hardware_interface::StateInterface linear_acceleration_y{
70-
sensor_name_, imu_interface_names_[8], &linear_acceleration_values_[1]};
71-
hardware_interface::StateInterface linear_acceleration_z{
72-
sensor_name_, imu_interface_names_[9], &linear_acceleration_values_[2]};
67+
auto linear_acceleration_x = std::make_shared<hardware_interface::StateInterface>(
68+
sensor_name_, imu_interface_names_[7], &linear_acceleration_values_[0]);
69+
auto linear_acceleration_y = std::make_shared<hardware_interface::StateInterface>(
70+
sensor_name_, imu_interface_names_[8], &linear_acceleration_values_[1]);
71+
auto linear_acceleration_z = std::make_shared<hardware_interface::StateInterface>(
72+
sensor_name_, imu_interface_names_[9], &linear_acceleration_values_[2]);
7373

7474
// create local state interface vector
7575
std::vector<hardware_interface::LoanedStateInterface> temp_state_interfaces;

controller_interface/test/test_semantic_component_interface.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -94,9 +94,12 @@ TEST_F(SemanticComponentInterfaceTest, validate_state_interfaces)
9494
std::vector<double> interface_values = {1.1, 3.3, 5.5};
9595

9696
// assign 1.1 to interface_1, 3.3 to interface_3 and 5.5 to interface_5
97-
hardware_interface::StateInterface interface_1{component_name_, "1", &interface_values[0]};
98-
hardware_interface::StateInterface interface_3{component_name_, "3", &interface_values[1]};
99-
hardware_interface::StateInterface interface_5{component_name_, "5", &interface_values[2]};
97+
auto interface_1 = std::make_shared<hardware_interface::StateInterface>(
98+
component_name_, "1", &interface_values[0]);
99+
auto interface_3 = std::make_shared<hardware_interface::StateInterface>(
100+
component_name_, "3", &interface_values[1]);
101+
auto interface_5 = std::make_shared<hardware_interface::StateInterface>(
102+
component_name_, "5", &interface_values[2]);
100103

101104
// create local state interface vector
102105
std::vector<hardware_interface::LoanedStateInterface> temp_state_interfaces;

controller_manager/CMakeLists.txt

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,6 @@ ament_target_dependencies(controller_manager PUBLIC ${THIS_PACKAGE_INCLUDE_DEPEN
3838
# Causes the visibility macros to use dllexport rather than dllimport,
3939
# which is appropriate when building the dll but not consuming it.
4040
target_compile_definitions(controller_manager PRIVATE "CONTROLLER_MANAGER_BUILDING_DLL")
41-
4241
add_executable(ros2_control_node src/ros2_control_node.cpp)
4342
target_link_libraries(ros2_control_node PRIVATE
4443
controller_manager

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 31 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@
3535
#include "controller_manager_msgs/srv/list_hardware_components.hpp"
3636
#include "controller_manager_msgs/srv/list_hardware_interfaces.hpp"
3737
#include "controller_manager_msgs/srv/load_controller.hpp"
38+
#include "controller_manager_msgs/srv/register_sub_controller_manager.hpp"
3839
#include "controller_manager_msgs/srv/reload_controller_libraries.hpp"
3940
#include "controller_manager_msgs/srv/set_hardware_component_state.hpp"
4041
#include "controller_manager_msgs/srv/switch_controller.hpp"
@@ -53,7 +54,6 @@
5354
#include "rclcpp/parameter.hpp"
5455
#include "rclcpp/rclcpp.hpp"
5556
#include "std_msgs/msg/string.hpp"
56-
5757
namespace controller_manager
5858
{
5959
using ControllersListIterator = std::vector<controller_manager::ControllerSpec>::const_iterator;
@@ -202,6 +202,27 @@ class ControllerManager : public rclcpp::Node
202202
CONTROLLER_MANAGER_PUBLIC
203203
void init_services();
204204

205+
CONTROLLER_MANAGER_PUBLIC
206+
void configure_controller_manager();
207+
208+
CONTROLLER_MANAGER_PUBLIC
209+
void init_distributed_main_controller_services();
210+
211+
CONTROLLER_MANAGER_PUBLIC
212+
void register_sub_controller_manager_srv_cb(
213+
const std::shared_ptr<controller_manager_msgs::srv::RegisterSubControllerManager::Request>
214+
request,
215+
std::shared_ptr<controller_manager_msgs::srv::RegisterSubControllerManager::Response> response);
216+
217+
CONTROLLER_MANAGER_PUBLIC
218+
void add_hardware_state_publishers();
219+
220+
CONTROLLER_MANAGER_PUBLIC
221+
void add_hardware_command_forwarders();
222+
223+
CONTROLLER_MANAGER_PUBLIC
224+
void register_sub_controller_manager();
225+
205226
CONTROLLER_MANAGER_PUBLIC
206227
controller_interface::ControllerInterfaceBaseSharedPtr add_controller_impl(
207228
const ControllerSpec & controller);
@@ -407,6 +428,10 @@ class ControllerManager : public rclcpp::Node
407428
*/
408429
rclcpp::CallbackGroup::SharedPtr best_effort_callback_group_;
409430

431+
bool distributed_ = false;
432+
bool sub_controller_manager_ = false;
433+
434+
rclcpp::CallbackGroup::SharedPtr distributed_system_srv_callback_group_;
410435
/**
411436
* The RTControllerListWrapper class wraps a double-buffered list of controllers
412437
* to avoid needing to lock the real-time thread when switching controllers in
@@ -504,6 +529,11 @@ class ControllerManager : public rclcpp::Node
504529
rclcpp::Service<controller_manager_msgs::srv::SetHardwareComponentState>::SharedPtr
505530
set_hardware_component_state_service_;
506531

532+
// services for distributed control
533+
std::mutex central_controller_manager_srv_lock_;
534+
rclcpp::Service<controller_manager_msgs::srv::RegisterSubControllerManager>::SharedPtr
535+
register_sub_controller_manager_srv_;
536+
507537
std::vector<std::string> activate_request_, deactivate_request_;
508538
std::vector<std::string> to_chained_mode_request_, from_chained_mode_request_;
509539
std::vector<std::string> activate_command_interface_request_,

0 commit comments

Comments
 (0)