Skip to content

Commit

Permalink
Deprecate method names that use CamelCase in rclcpp_components (#1716)
Browse files Browse the repository at this point in the history
* Rename methods in ComponentManager to use snake_case

Signed-off-by: Rebecca Butler <rebecca@openrobotics.org>

* Deprecate old method names

Signed-off-by: Rebecca Butler <rebecca@openrobotics.org>
  • Loading branch information
rebecca-butler committed Jul 19, 2021
1 parent 86c079d commit 0d6d9e6
Show file tree
Hide file tree
Showing 2 changed files with 60 additions and 18 deletions.
62 changes: 52 additions & 10 deletions rclcpp_components/include/rclcpp_components/component_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ class ComponentManager : public rclcpp::Node
virtual ~ComponentManager();

/// Return a list of valid loadable components in a given package.
/*
/**
* \param package_name name of the package
* \param resource_index name of the executable
* \throws ComponentManagerException if the resource was not found or a invalid resource entry
Expand All @@ -122,7 +122,7 @@ class ComponentManager : public rclcpp::Node
const std::string & resource_index = "rclcpp_components") const;

/// Instantiate a component from a dynamic library.
/*
/**
* \param resource a component resource (class name + library path)
* \return a NodeFactory interface
*/
Expand All @@ -132,16 +132,16 @@ class ComponentManager : public rclcpp::Node

protected:
/// Create node options for loaded component
/*
/**
* \param request information with the node to load
* \return node options
*/
RCLCPP_COMPONENTS_PUBLIC
virtual rclcpp::NodeOptions
CreateNodeOptions(const std::shared_ptr<LoadNode::Request> request);
create_node_options(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
* and/or additional arguments.
*
Expand All @@ -155,27 +155,55 @@ class ComponentManager : public rclcpp::Node
*/
RCLCPP_COMPONENTS_PUBLIC
virtual void
OnLoadNode(
on_load_node(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<LoadNode::Request> request,
std::shared_ptr<LoadNode::Response> response);

/**
* \deprecated Use on_load_node() instead
*/
[[deprecated("Use on_load_node() instead")]]
RCLCPP_COMPONENTS_PUBLIC
virtual void
OnLoadNode(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<LoadNode::Request> request,
std::shared_ptr<LoadNode::Response> response)
{
on_load_node(request_header, request, response);
}

/// Service callback to unload a node in the component
/*
/**
* \param request_header unused
* \param request unique identifier to remove from the component
* \param response true on the success field if the node unload was succefully, otherwise false
* and the error_message field contains the error.
*/
RCLCPP_COMPONENTS_PUBLIC
virtual void
OnUnloadNode(
on_unload_node(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<UnloadNode::Request> request,
std::shared_ptr<UnloadNode::Response> response);

/**
* \deprecated Use on_unload_node() instead
*/
[[deprecated("Use on_unload_node() instead")]]
RCLCPP_COMPONENTS_PUBLIC
virtual void
OnUnloadNode(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<UnloadNode::Request> request,
std::shared_ptr<UnloadNode::Response> response)
{
on_unload_node(request_header, request, response);
}

/// Service callback to get the list of nodes in the component
/*
/**
* Return a two list: one with the unique identifiers and other with full name of the nodes.
*
* \param request_header unused
Expand All @@ -184,11 +212,25 @@ class ComponentManager : public rclcpp::Node
*/
RCLCPP_COMPONENTS_PUBLIC
virtual void
OnListNodes(
on_list_nodes(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<ListNodes::Request> request,
std::shared_ptr<ListNodes::Response> response);

/**
* \deprecated Use on_list_nodes() instead
*/
[[deprecated("Use on_list_nodes() instead")]]
RCLCPP_COMPONENTS_PUBLIC
virtual void
OnListNodes(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<ListNodes::Request> request,
std::shared_ptr<ListNodes::Response> response)
{
on_list_nodes(request_header, request, response);
}

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

Expand Down
16 changes: 8 additions & 8 deletions rclcpp_components/src/component_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,13 @@ ComponentManager::ComponentManager(
{
loadNode_srv_ = create_service<LoadNode>(
"~/_container/load_node",
std::bind(&ComponentManager::OnLoadNode, this, _1, _2, _3));
std::bind(&ComponentManager::on_load_node, this, _1, _2, _3));
unloadNode_srv_ = create_service<UnloadNode>(
"~/_container/unload_node",
std::bind(&ComponentManager::OnUnloadNode, this, _1, _2, _3));
std::bind(&ComponentManager::on_unload_node, this, _1, _2, _3));
listNodes_srv_ = create_service<ListNodes>(
"~/_container/list_nodes",
std::bind(&ComponentManager::OnListNodes, this, _1, _2, _3));
std::bind(&ComponentManager::on_list_nodes, this, _1, _2, _3));
}

ComponentManager::~ComponentManager()
Expand Down Expand Up @@ -122,7 +122,7 @@ ComponentManager::create_component_factory(const ComponentResource & resource)
}

rclcpp::NodeOptions
ComponentManager::CreateNodeOptions(const std::shared_ptr<LoadNode::Request> request)
ComponentManager::create_node_options(const std::shared_ptr<LoadNode::Request> request)
{
std::vector<rclcpp::Parameter> parameters;
for (const auto & p : request->parameters) {
Expand Down Expand Up @@ -167,7 +167,7 @@ ComponentManager::CreateNodeOptions(const std::shared_ptr<LoadNode::Request> req
}

void
ComponentManager::OnLoadNode(
ComponentManager::on_load_node(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<LoadNode::Request> request,
std::shared_ptr<LoadNode::Response> response)
Expand All @@ -187,7 +187,7 @@ ComponentManager::OnLoadNode(
continue;
}

auto options = CreateNodeOptions(request);
auto options = create_node_options(request);
auto node_id = unique_id_++;

if (0 == node_id) {
Expand Down Expand Up @@ -237,7 +237,7 @@ ComponentManager::OnLoadNode(
}

void
ComponentManager::OnUnloadNode(
ComponentManager::on_unload_node(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<UnloadNode::Request> request,
std::shared_ptr<UnloadNode::Response> response)
Expand All @@ -262,7 +262,7 @@ ComponentManager::OnUnloadNode(
}

void
ComponentManager::OnListNodes(
ComponentManager::on_list_nodes(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<ListNodes::Request> request,
std::shared_ptr<ListNodes::Response> response)
Expand Down

0 comments on commit 0d6d9e6

Please sign in to comment.