Skip to content

Commit

Permalink
make functions public & virtual
Browse files Browse the repository at this point in the history
Signed-off-by: Karsten Knese <karsten@openrobotics.org>
  • Loading branch information
Karsten1987 committed Apr 14, 2020
1 parent 44fa4fe commit d81d494
Show file tree
Hide file tree
Showing 6 changed files with 35 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef COMPONENT_MANAGER_HPP__
#define COMPONENT_MANAGER_HPP__
#ifndef RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__
#define RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__

#include <map>
#include <memory>
Expand All @@ -33,6 +33,11 @@

#include "rclcpp_components/node_factory.hpp"

namespace class_loader
{
class ClassLoader;
} // namespace class_loader

namespace rclcpp_components
{

Expand All @@ -57,31 +62,34 @@ class ComponentManager : public rclcpp::Node
using ComponentResource = std::pair<std::string, std::string>;

ComponentManager(
std::weak_ptr<rclcpp::executor::Executor> executor);
std::weak_ptr<rclcpp::executor::Executor> executor,
std::string node_name = "ComponentManager");

~ComponentManager();
virtual ~ComponentManager();

/// Return a list of valid loadable components in a given package.
std::vector<ComponentResource>
get_component_resources(const std::string & package_name) const;
virtual std::vector<ComponentResource>
get_component_resources(
const std::string & package_name,
const std::string & resource_index = "rclcpp_components") const;

std::shared_ptr<rclcpp_components::NodeFactory>
virtual std::shared_ptr<rclcpp_components::NodeFactory>
create_component_factory(const ComponentResource & resource);

private:
void
protected:
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);

void
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);

void
virtual void
OnListNodes(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<ListNodes::Request> request,
Expand All @@ -90,7 +98,7 @@ class ComponentManager : public rclcpp::Node
private:
std::weak_ptr<rclcpp::executor::Executor> executor_;

uint64_t unique_id {1};
uint64_t unique_id_ {1};
std::map<std::string, std::unique_ptr<class_loader::ClassLoader>> loaders_;
std::map<uint64_t, rclcpp_components::NodeInstanceWrapper> node_wrappers_;

Expand All @@ -101,4 +109,4 @@ class ComponentManager : public rclcpp::Node

} // namespace rclcpp_components

#endif // COMPONENT_MANAGER_HPP__
#endif // RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__
2 changes: 1 addition & 1 deletion rclcpp_components/src/component_container.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include "rclcpp/rclcpp.hpp"

#include "component_manager.hpp"
#include "rclcpp_components/component_manager.hpp"

int main(int argc, char * argv[])
{
Expand Down
2 changes: 1 addition & 1 deletion rclcpp_components/src/component_container_mt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include "rclcpp/rclcpp.hpp"

#include "component_manager.hpp"
#include "rclcpp_components/component_manager.hpp"

int main(int argc, char * argv[])
{
Expand Down
16 changes: 10 additions & 6 deletions rclcpp_components/src/component_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "component_manager.hpp"
#include "rclcpp_components/component_manager.hpp"

#include <functional>
#include <memory>
#include <string>
#include <utility>
#include <vector>

#include "ament_index_cpp/get_resource.hpp"
#include "class_loader/class_loader.hpp"
#include "rcpputils/filesystem_helper.hpp"
#include "rcpputils/split.hpp"

Expand All @@ -29,8 +31,9 @@ namespace rclcpp_components
{

ComponentManager::ComponentManager(
std::weak_ptr<rclcpp::executor::Executor> executor)
: Node("ComponentManager"),
std::weak_ptr<rclcpp::executor::Executor> executor,
std::string node_name)
: Node(std::move(node_name)),
executor_(executor)
{
loadNode_srv_ = create_service<LoadNode>(
Expand All @@ -57,13 +60,14 @@ ComponentManager::~ComponentManager()
}

std::vector<ComponentManager::ComponentResource>
ComponentManager::get_component_resources(const std::string & package_name) const
ComponentManager::get_component_resources(
const std::string & package_name, const std::string & resource_index) const
{
std::string content;
std::string base_path;
if (
!ament_index_cpp::get_resource(
"rclcpp_components", package_name, content, &base_path))
resource_index, package_name, content, &base_path))
{
throw ComponentManagerException("Could not find requested resource in ament index");
}
Expand Down Expand Up @@ -176,7 +180,7 @@ ComponentManager::OnLoadNode(
}
}

auto node_id = unique_id++;
auto node_id = unique_id_++;

if (0 == node_id) {
// This puts a technical limit on the number of times you can add a component.
Expand Down
2 changes: 1 addition & 1 deletion rclcpp_components/test/test_component_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include <memory>

#include "component_manager.hpp"
#include "rclcpp_components/component_manager.hpp"

#include "rcpputils/filesystem_helper.hpp"

Expand Down
2 changes: 1 addition & 1 deletion rclcpp_components/test/test_component_manager_api.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include "composition_interfaces/srv/unload_node.hpp"
#include "composition_interfaces/srv/list_nodes.hpp"

#include "component_manager.hpp"
#include "rclcpp_components/component_manager.hpp"

using namespace std::chrono_literals;

Expand Down

0 comments on commit d81d494

Please sign in to comment.