Skip to content

Commit

Permalink
Add SetNodeOptions function
Browse files Browse the repository at this point in the history
  • Loading branch information
rebecca-butler committed Jun 30, 2021
1 parent 9f7cedc commit a80fa14
Show file tree
Hide file tree
Showing 2 changed files with 40 additions and 51 deletions.
49 changes: 14 additions & 35 deletions rclcpp_components/include/rclcpp_components/component_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,20 @@ class ComponentManager : public rclcpp::Node
create_component_factory(const ComponentResource & resource);

protected:
/// Set node options for componenet
/*
* \param parameters node parameters
* \param remap_rules node remap rules
* \param request information with the node to load
* \return node options
*/
RCLCPP_COMPONENTS_PUBLIC
virtual rclcpp::NodeOptions
SetNodeOptions(
std::vector<rclcpp::Parameter> parameters,
std::vector<std::string> remap_rules,
const std::shared_ptr<LoadNode::Request> request);

/// Service callback to load a new node in the component
/*
* This function allows to add parameters, remap rules, a specific node, name a namespace
Expand Down Expand Up @@ -180,41 +194,6 @@ class ComponentManager : public rclcpp::Node
const std::shared_ptr<ListNodes::Request> request,
std::shared_ptr<ListNodes::Response> response);

RCLCPP_COMPONENTS_PUBLIC
const std::weak_ptr<rclcpp::Executor>
GetExecutor() const
{
return executor_;
}

RCLCPP_COMPONENTS_PUBLIC
uint64_t
GetUniqueId()
{
return unique_id_;
}

RCLCPP_COMPONENTS_PUBLIC
void
SetUniqueId(uint64_t id)
{
unique_id_ = id;
}

RCLCPP_COMPONENTS_PUBLIC
rclcpp_components::NodeInstanceWrapper
GetNodeWrapper(uint64_t node_id)
{
return node_wrappers_[node_id];
}

RCLCPP_COMPONENTS_PUBLIC
void
SetNodeWrapper(uint64_t node_id, rclcpp_components::NodeInstanceWrapper node_wrapper)
{
node_wrappers_[node_id] = node_wrapper;
}

private:
std::weak_ptr<rclcpp::Executor> executor_;

Expand Down
42 changes: 26 additions & 16 deletions rclcpp_components/src/component_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,6 +121,31 @@ ComponentManager::create_component_factory(const ComponentResource & resource)
return {};
}

rclcpp::NodeOptions
ComponentManager::SetNodeOptions(
std::vector<rclcpp::Parameter> parameters,
std::vector<std::string> remap_rules,
const std::shared_ptr<LoadNode::Request> request)
{
auto options = rclcpp::NodeOptions()
.use_global_arguments(false)
.parameter_overrides(parameters)
.arguments(remap_rules);

for (const auto & a : request->extra_arguments) {
const rclcpp::Parameter extra_argument = rclcpp::Parameter::from_parameter_msg(a);
if (extra_argument.get_name() == "use_intra_process_comms") {
if (extra_argument.get_type() != rclcpp::ParameterType::PARAMETER_BOOL) {
throw ComponentManagerException(
"Extra component argument 'use_intra_process_comms' must be a boolean");
}
options.use_intra_process_comms(extra_argument.get_value<bool>());
}
}

return options;
}

void
ComponentManager::OnLoadNode(
const std::shared_ptr<rmw_request_id_t> request_header,
Expand Down Expand Up @@ -165,22 +190,7 @@ ComponentManager::OnLoadNode(
remap_rules.push_back("__ns:=" + request->node_namespace);
}

auto options = rclcpp::NodeOptions()
.use_global_arguments(false)
.parameter_overrides(parameters)
.arguments(remap_rules);

for (const auto & a : request->extra_arguments) {
const rclcpp::Parameter extra_argument = rclcpp::Parameter::from_parameter_msg(a);
if (extra_argument.get_name() == "use_intra_process_comms") {
if (extra_argument.get_type() != rclcpp::ParameterType::PARAMETER_BOOL) {
throw ComponentManagerException(
"Extra component argument 'use_intra_process_comms' must be a boolean");
}
options.use_intra_process_comms(extra_argument.get_value<bool>());
}
}

auto options = SetNodeOptions(parameters, remap_rules, request);
auto node_id = unique_id_++;

if (0 == node_id) {
Expand Down

0 comments on commit a80fa14

Please sign in to comment.