-
Notifications
You must be signed in to change notification settings - Fork 356
Addition of a Default Node for Hardware Component #2348
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from 18 commits
bdf7ad4
e7e319b
b077541
adcb985
cad5970
d56e13f
c0cc99c
fdb8162
88b8136
4e14661
c1c726d
2d70891
7750bd7
991d12a
83b5631
653d8ad
432b70d
93636da
7ec6ae0
0089ede
d0f48ea
60b9ddd
4e4a248
afed96d
a96acbd
98c58e3
b167a23
d43af23
e1724d4
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -186,6 +186,26 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod | |
info_.thread_priority); | ||
async_handler_->start_thread(); | ||
} | ||
|
||
if (auto locked_executor = params.executor.lock()) | ||
{ | ||
std::string node_name = params.hardware_info.name; | ||
std::transform( | ||
node_name.begin(), node_name.end(), node_name.begin(), | ||
[](unsigned char c) { return std::tolower(c); }); | ||
std::replace(node_name.begin(), node_name.end(), '/', '_'); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Should we later convert it to lower case just in case?. What's your opinion here?. I'm okay to merge it as it is and then we can deal with it later. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. refer |
||
hardware_component_node_ = std::make_shared<rclcpp::Node>(node_name); | ||
locked_executor->add_node(hardware_component_node_->get_node_base_interface()); | ||
} | ||
else | ||
{ | ||
RCLCPP_WARN( | ||
params.logger, | ||
"Executor is not available during hardware component initialization for '%s'. Skipping " | ||
"node creation!", | ||
params.hardware_info.name.c_str()); | ||
} | ||
|
||
hardware_interface::HardwareComponentInterfaceParams interface_params; | ||
interface_params.hardware_info = info_; | ||
interface_params.executor = params.executor; | ||
|
@@ -646,6 +666,12 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod | |
*/ | ||
rclcpp::Clock::SharedPtr get_clock() const { return actuator_clock_; } | ||
|
||
/// Get the default node of the ActuatorInterface. | ||
/** | ||
* \return node of the ActuatorInterface. | ||
*/ | ||
rclcpp::Node::SharedPtr get_node() const { return hardware_component_node_; } | ||
|
||
/// Get the hardware info of the ActuatorInterface. | ||
/** | ||
* \return hardware info of the ActuatorInterface. | ||
|
@@ -702,6 +728,7 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod | |
private: | ||
rclcpp::Clock::SharedPtr actuator_clock_; | ||
rclcpp::Logger actuator_logger_; | ||
rclcpp::Node::SharedPtr hardware_component_node_ = nullptr; | ||
// interface names to Handle accessed through getters/setters | ||
std::unordered_map<std::string, StateInterface::SharedPtr> actuator_states_; | ||
std::unordered_map<std::string, CommandInterface::SharedPtr> actuator_commands_; | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -190,6 +190,26 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI | |
info_.thread_priority); | ||
async_handler_->start_thread(); | ||
} | ||
|
||
if (auto locked_executor = params.executor.lock()) | ||
saikishor marked this conversation as resolved.
Show resolved
Hide resolved
|
||
{ | ||
std::string node_name = params.hardware_info.name; | ||
std::transform( | ||
node_name.begin(), node_name.end(), node_name.begin(), | ||
[](unsigned char c) { return std::tolower(c); }); | ||
std::replace(node_name.begin(), node_name.end(), '/', '_'); | ||
hardware_component_node_ = std::make_shared<rclcpp::Node>(node_name); | ||
locked_executor->add_node(hardware_component_node_->get_node_base_interface()); | ||
} | ||
else | ||
{ | ||
RCLCPP_WARN( | ||
params.logger, | ||
"Executor is not available during hardware component initialization for '%s'. Skipping " | ||
"node creation!", | ||
Comment on lines
+208
to
+209
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. How often does this happen? Can we try for the lock more than once? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This doesn't happen as long as the Executor is a valid pointer. We had to add it as we started adding this new API now, so all the tests are calling this without a valid executor. |
||
params.hardware_info.name.c_str()); | ||
} | ||
|
||
hardware_interface::HardwareComponentInterfaceParams interface_params; | ||
interface_params.hardware_info = info_; | ||
interface_params.executor = params.executor; | ||
|
@@ -677,6 +697,12 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI | |
*/ | ||
rclcpp::Clock::SharedPtr get_clock() const { return system_clock_; } | ||
|
||
/// Get the default node of the ActuatorInterface. | ||
/** | ||
* \return node of the ActuatorInterface. | ||
*/ | ||
rclcpp::Node::SharedPtr get_node() const { return hardware_component_node_; } | ||
|
||
/// Get the hardware info of the SystemInterface. | ||
/** | ||
* \return hardware info of the SystemInterface. | ||
|
@@ -743,6 +769,7 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI | |
private: | ||
rclcpp::Clock::SharedPtr system_clock_; | ||
rclcpp::Logger system_logger_; | ||
rclcpp::Node::SharedPtr hardware_component_node_ = nullptr; | ||
// interface names to Handle accessed through getters/setters | ||
std::unordered_map<std::string, StateInterface::SharedPtr> system_states_; | ||
std::unordered_map<std::string, CommandInterface::SharedPtr> system_commands_; | ||
|
Uh oh!
There was an error while loading. Please reload this page.