Motion planner (MoveIt) and Task planner (Plansys) integration
This commit is contained in:
parent
0a735b87c9
commit
000ddb4831
43 changed files with 1402 additions and 379 deletions
|
@ -1,4 +1,5 @@
|
|||
#include "component_manager/component_manager.hpp"
|
||||
#include "component_manager/node_component.hpp"
|
||||
#include "component_manager/publisher_component.hpp"
|
||||
#include "component_manager/subscriber_component.hpp"
|
||||
#include "component_manager/service_component.hpp"
|
||||
|
@ -50,6 +51,9 @@ static rclcpp::NodeOptions create_options(
|
|||
case config::NodeOption::NodeType::Client:
|
||||
args.push_back(DEFAULT_CLIENT_NAME + ":=" + node_opts.name);
|
||||
break;
|
||||
case config::NodeOption::NodeType::Node:
|
||||
args.erase(args.end());
|
||||
break;
|
||||
}
|
||||
|
||||
opts.arguments(args);
|
||||
|
@ -87,8 +91,11 @@ void ComponentManager::register_components(
|
|||
auto loader = new class_loader::ClassLoader(comp.library);
|
||||
auto classes =
|
||||
loader->getAvailableClasses<rclcpp_components::NodeFactory>();
|
||||
|
||||
for (auto clazz: classes)
|
||||
{
|
||||
if (clazz != class_name)
|
||||
continue;
|
||||
rclcpp::NodeOptions opts = create_default_options(ns);
|
||||
if (clazz == class_name)
|
||||
{
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue