Skip to content

Commit a921ec3

Browse files
committed
add parameter for setting publish period
1 parent af8ab04 commit a921ec3

File tree

8 files changed

+62
-19
lines changed

8 files changed

+62
-19
lines changed

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -198,13 +198,20 @@ class ControllerManager : public rclcpp::Node
198198
CONTROLLER_MANAGER_PUBLIC
199199
unsigned int get_update_rate() const;
200200

201+
// Per controller update rate support
202+
CONTROLLER_MANAGER_PUBLIC
203+
std::chrono::milliseconds distributed_interfaces_publish_period() const;
204+
201205
protected:
202206
CONTROLLER_MANAGER_PUBLIC
203207
void init_services();
204208

205209
CONTROLLER_MANAGER_PUBLIC
206210
void configure_controller_manager();
207211

212+
CONTROLLER_MANAGER_PUBLIC
213+
void init_distributed_sub_controller_manager();
214+
208215
CONTROLLER_MANAGER_PUBLIC
209216
void init_distributed_main_controller_services();
210217

@@ -430,6 +437,7 @@ class ControllerManager : public rclcpp::Node
430437

431438
bool distributed_ = false;
432439
bool sub_controller_manager_ = false;
440+
std::chrono::milliseconds distributed_interfaces_publish_period_ = std::chrono::milliseconds(12);
433441

434442
rclcpp::CallbackGroup::SharedPtr distributed_system_srv_callback_group_;
435443
/**

controller_manager/src/controller_manager.cpp

Lines changed: 29 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -379,9 +379,7 @@ void ControllerManager::configure_controller_manager()
379379
bool central_controller_manager = distributed_ && !sub_controller_manager_;
380380
if (distributed_sub_controller_manager)
381381
{
382-
add_hardware_state_publishers();
383-
add_hardware_command_forwarders();
384-
register_sub_controller_manager();
382+
init_distributed_sub_controller_manager();
385383
}
386384
// This means we are the central controller manager
387385
else if (central_controller_manager)
@@ -400,6 +398,25 @@ void ControllerManager::configure_controller_manager()
400398
}
401399
}
402400

401+
void ControllerManager::init_distributed_sub_controller_manager()
402+
{
403+
int64_t distributed_interfaces_publish_period;
404+
if (get_parameter("distributed_interfaces_publish_period", distributed_interfaces_publish_period))
405+
{
406+
distributed_interfaces_publish_period_ =
407+
std::chrono::milliseconds(distributed_interfaces_publish_period);
408+
}
409+
else
410+
{
411+
RCLCPP_WARN(
412+
get_logger(),
413+
"'distributed_interfaces_publish_period' parameter not set, using default value.");
414+
}
415+
add_hardware_state_publishers();
416+
add_hardware_command_forwarders();
417+
register_sub_controller_manager();
418+
}
419+
403420
void ControllerManager::init_distributed_main_controller_services()
404421
{
405422
distributed_system_srv_callback_group_ =
@@ -490,7 +507,8 @@ void ControllerManager::add_hardware_state_publishers()
490507
{
491508
std::vector<std::shared_ptr<distributed_control::StatePublisher>> state_publishers_vec;
492509
state_publishers_vec.reserve(resource_manager_->available_state_interfaces().size());
493-
state_publishers_vec = resource_manager_->create_hardware_state_publishers(get_namespace());
510+
state_publishers_vec = resource_manager_->create_hardware_state_publishers(
511+
get_namespace(), distributed_interfaces_publish_period());
494512

495513
for (auto const & state_publisher : state_publishers_vec)
496514
{
@@ -511,7 +529,8 @@ void ControllerManager::add_hardware_command_forwarders()
511529
{
512530
std::vector<std::shared_ptr<distributed_control::CommandForwarder>> command_forwarder_vec;
513531
command_forwarder_vec.reserve(resource_manager_->available_command_interfaces().size());
514-
command_forwarder_vec = resource_manager_->create_hardware_command_forwarders(get_namespace());
532+
command_forwarder_vec = resource_manager_->create_hardware_command_forwarders(
533+
get_namespace(), distributed_interfaces_publish_period());
515534

516535
for (auto const & command_forwarder : command_forwarder_vec)
517536
{
@@ -2235,6 +2254,11 @@ std::pair<std::string, std::string> ControllerManager::split_command_interface(
22352254

22362255
unsigned int ControllerManager::get_update_rate() const { return update_rate_; }
22372256

2257+
std::chrono::milliseconds ControllerManager::distributed_interfaces_publish_period() const
2258+
{
2259+
return distributed_interfaces_publish_period_;
2260+
}
2261+
22382262
void ControllerManager::propagate_deactivation_of_chained_mode(
22392263
const std::vector<ControllerSpec> & controllers)
22402264
{

hardware_interface/include/hardware_interface/distributed_control_interface/command_forwarder.hpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
#ifndef DISTRIBUTED_CONTROL__COMMAND_FORWARDER_HPP_
22
#define DISTRIBUTED_CONTROL__COMMAND_FORWARDER_HPP_
33

4+
#include <chrono>
45
#include <memory>
56
#include <string>
67
#include <vector>
@@ -22,8 +23,8 @@ class CommandForwarder final
2223
{
2324
public:
2425
explicit CommandForwarder(
25-
std::unique_ptr<hardware_interface::LoanedCommandInterface> loaned_command_interface_ptr_,
26-
const std::string & ns = "");
26+
std::unique_ptr<hardware_interface::LoanedCommandInterface> loaned_command_interface_ptr,
27+
std::chrono::milliseconds period_in_ms, const std::string & ns = "");
2728

2829
CommandForwarder() = delete;
2930

@@ -53,6 +54,8 @@ class CommandForwarder final
5354

5455
std::unique_ptr<hardware_interface::LoanedCommandInterface> loaned_command_interface_ptr_;
5556
const std::string namespace_;
57+
const std::chrono::milliseconds period_in_ms_;
58+
5659
const std::string topic_name_;
5760
std::string subscription_topic_name_;
5861
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;

hardware_interface/include/hardware_interface/distributed_control_interface/state_publisher.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ class StatePublisher final
2222
public:
2323
explicit StatePublisher(
2424
std::unique_ptr<hardware_interface::LoanedStateInterface> loaned_state_interface_ptr,
25-
const std::string & ns = "");
25+
std::chrono::milliseconds period_in_ms, const std::string & ns = "");
2626

2727
StatePublisher() = delete;
2828

@@ -49,6 +49,8 @@ class StatePublisher final
4949

5050
std::unique_ptr<hardware_interface::LoanedStateInterface> loaned_state_interface_ptr_;
5151
const std::string namespace_;
52+
std::chrono::milliseconds period_in_ms_;
53+
5254
const std::string topic_name_;
5355
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
5456
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr state_value_pub_;

hardware_interface/include/hardware_interface/resource_manager.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -141,10 +141,11 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
141141
std::shared_ptr<distributed_control::SubControllerManagerWrapper> sub_controller_manager);
142142

143143
std::vector<std::shared_ptr<distributed_control::StatePublisher>>
144-
create_hardware_state_publishers(const std::string & ns);
144+
create_hardware_state_publishers(const std::string & ns, std::chrono::milliseconds update_period);
145145

146146
std::vector<std::shared_ptr<distributed_control::CommandForwarder>>
147-
create_hardware_command_forwarders(const std::string & ns);
147+
create_hardware_command_forwarders(
148+
const std::string & ns, std::chrono::milliseconds update_period);
148149

149150
std::pair<bool, std::shared_ptr<distributed_control::CommandForwarder>> find_command_forwarder(
150151
const std::string & key);

hardware_interface/src/hardware_interface/distributed_control_interface/command_forwarder.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,9 @@ namespace distributed_control
1313

1414
CommandForwarder::CommandForwarder(
1515
std::unique_ptr<hardware_interface::LoanedCommandInterface> loaned_command_interface_ptr,
16-
const std::string & ns)
16+
std::chrono::milliseconds period_in_ms, const std::string & ns)
1717
: loaned_command_interface_ptr_(std::move(loaned_command_interface_ptr)),
18+
period_in_ms_(period_in_ms),
1819
namespace_(ns),
1920
topic_name_(loaned_command_interface_ptr_->get_underscore_separated_name() + "_command_state")
2021
{
@@ -25,8 +26,8 @@ CommandForwarder::CommandForwarder(
2526

2627
state_value_pub_ = node_->create_publisher<std_msgs::msg::Float64>(topic_name_, 10);
2728
// TODO(Manuel): We should check if we cannot detect changes to LoanedStateInterface's value and only publish then
28-
timer_ =
29-
node_->create_wall_timer(50ms, std::bind(&CommandForwarder::publish_value_on_timer, this));
29+
timer_ = node_->create_wall_timer(
30+
period_in_ms_, std::bind(&CommandForwarder::publish_value_on_timer, this));
3031
RCLCPP_INFO(node_->get_logger(), "Creating CommandForwarder<%s>.", topic_name_.c_str());
3132
}
3233

hardware_interface/src/hardware_interface/distributed_control_interface/state_publisher.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,9 @@ namespace distributed_control
1313

1414
StatePublisher::StatePublisher(
1515
std::unique_ptr<hardware_interface::LoanedStateInterface> loaned_state_interface_ptr,
16-
const std::string & ns)
16+
std::chrono::milliseconds period_in_ms, const std::string & ns)
1717
: loaned_state_interface_ptr_(std::move(loaned_state_interface_ptr)),
18+
period_in_ms_(period_in_ms),
1819
namespace_(ns),
1920
topic_name_(loaned_state_interface_ptr_->get_underscore_separated_name() + "_state")
2021
{
@@ -25,7 +26,8 @@ StatePublisher::StatePublisher(
2526

2627
state_value_pub_ = node_->create_publisher<std_msgs::msg::Float64>(topic_name_, 10);
2728
// TODO(Manuel): We should check if we cannot detect changes to LoanedStateInterface's value and only publish then
28-
timer_ = node_->create_wall_timer(50ms, std::bind(&StatePublisher::publish_value_on_timer, this));
29+
timer_ = node_->create_wall_timer(
30+
period_in_ms_, std::bind(&StatePublisher::publish_value_on_timer, this));
2931
RCLCPP_INFO(node_->get_logger(), "Creating StatePublisher<%s>.", topic_name_.c_str());
3032
}
3133

hardware_interface/src/resource_manager.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -954,7 +954,8 @@ ResourceManager::import_command_interfaces_of_sub_controller_manager(
954954
}
955955

956956
std::vector<std::shared_ptr<distributed_control::StatePublisher>>
957-
ResourceManager::create_hardware_state_publishers(const std::string & ns)
957+
ResourceManager::create_hardware_state_publishers(
958+
const std::string & ns, std::chrono::milliseconds update_period)
958959
{
959960
std::lock_guard<std::recursive_mutex> guard(resource_interfaces_lock_);
960961
std::vector<std::shared_ptr<distributed_control::StatePublisher>> state_publishers_vec;
@@ -965,7 +966,7 @@ ResourceManager::create_hardware_state_publishers(const std::string & ns)
965966
auto state_publisher = std::make_shared<distributed_control::StatePublisher>(
966967
std::move(std::make_unique<hardware_interface::LoanedStateInterface>(
967968
claim_state_interface(state_interface))),
968-
ns);
969+
update_period, ns);
969970

970971
resource_storage_->add_state_publisher(state_publisher);
971972
state_publishers_vec.push_back(state_publisher);
@@ -975,7 +976,8 @@ ResourceManager::create_hardware_state_publishers(const std::string & ns)
975976
}
976977

977978
std::vector<std::shared_ptr<distributed_control::CommandForwarder>>
978-
ResourceManager::create_hardware_command_forwarders(const std::string & ns)
979+
ResourceManager::create_hardware_command_forwarders(
980+
const std::string & ns, std::chrono::milliseconds update_period)
979981
{
980982
std::lock_guard<std::recursive_mutex> guard(resource_interfaces_lock_);
981983
std::vector<std::shared_ptr<distributed_control::CommandForwarder>> command_forwarders_vec;
@@ -986,7 +988,7 @@ ResourceManager::create_hardware_command_forwarders(const std::string & ns)
986988
auto command_forwarder = std::make_shared<distributed_control::CommandForwarder>(
987989
std::move(std::make_unique<hardware_interface::LoanedCommandInterface>(
988990
claim_command_interface(command_interface))),
989-
ns);
991+
update_period, ns);
990992

991993
resource_storage_->add_command_forwarder(command_forwarder);
992994
command_forwarders_vec.push_back(command_forwarder);

0 commit comments

Comments
 (0)