Skip to content
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

Add optional namespace field to task nodes #433

Merged
123 changes: 120 additions & 3 deletions tesseract_task_composer/README.rst
Original file line number Diff line number Diff line change
Expand Up @@ -53,24 +53,28 @@ This file allows you define Excutors and Tasks (aka Nodes).
MinLengthTask:
class: MinLengthTaskFactory
config:
namespace: MinLengthTask # (optional, defaults to parent yaml key name "MinLengthTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
DescartesMotionPlannerTask:
class: DescartesFMotionPlannerTaskFactory
config:
namespace: DescartesMotionPlannerTask # (optional, defaults to parent yaml key name "DescartesMotionPlannerTask")
conditional: true
inputs: [output_data]
outputs: [output_data]
format_result_as_input: false
DiscreteContactCheckTask:
class: DiscreteContactCheckTaskFactory
config:
namespace: DiscreteContactCheckTask # (optional, defaults to parent yaml key name "DiscreteContactCheckTask")
conditional: true
inputs: [output_data]
IterativeSplineParameterizationTask:
class: IterativeSplineParameterizationTaskFactory
config:
namespace: IterativeSplineParameterizationTask # (optional, defaults to parent yaml key name "IterativeSplineParameterizationTask")
conditional: true
inputs: [output_data]
outputs: [output_data]
Expand Down Expand Up @@ -150,31 +154,36 @@ Define the graph nodes and edges as shown in the config below.
MinLengthTask:
class: MinLengthTaskFactory
config:
namespace: MinLengthTask # (optional)
conditional: true
inputs: [input_data]
outputs: [output_data]
DescartesMotionPlannerTask:
class: DescartesFMotionPlannerTaskFactory
config:
namespace: DescartesMotionPlannerTask # (optional)
conditional: true
inputs: [output_data]
outputs: [output_data]
format_result_as_input: true
TrajOptMotionPlannerTask:
class: TrajOptMotionPlannerTaskFactory
config:
namespace: TrajOptMotionPlannerTask # (optional)
conditional: true
inputs: [output_data]
outputs: [output_data]
format_result_as_input: false
DiscreteContactCheckTask:
class: DiscreteContactCheckTaskFactory
config:
namespace: DiscreteContactCheckTask # (optional)
conditional: true
inputs: [output_data]
IterativeSplineParameterizationTask:
class: IterativeSplineParameterizationTaskFactory
config:
namespace: IterativeSplineParameterizationTask # (optional)
conditional: true
inputs: [output_data]
outputs: [output_data]
Expand All @@ -191,7 +200,7 @@ Define the graph nodes and edges as shown in the config below.
destinations: [ErrorTask, DoneTask]
terminals: [ErrorTask, DoneTask]

Leveraging a perviously defined task
Leveraging a previously defined task
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

When using a perviously defined task it is referenced using `task:` instead of `class:`.
Expand Down Expand Up @@ -226,6 +235,97 @@ Also you can indicate that it should abort if a terminal is reached by specifyin
destinations: [CartesianPipelineTask]
terminals: [CartesianPipelineTask]


Reusing a namespace across multiple tasks
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Sometimes it is desireable to reuse a particular configration of a task. To prevent the need from having to make two entries for the tasks you can use the namespace field under the task config.

Here is an example where the namespace field is used to reuse a contact check configuration.

.. code-block:: yaml

task_composer_plugins:
search_paths:
- /usr/local/lib
search_libraries:
- tesseract_task_composer_factories
executors:
default: TaskflowExecutor
plugins:
TaskflowExecutor:
class: TaskflowTaskComposerExecutorFactory
config:
threads: 5
tasks:
plugins:
FreespacePipeline:
class: GraphTaskFactory
config:
inputs: [input_data]
outputs: [output_data]
nodes:
DoneTask:
class: DoneTaskFactory
config:
conditional: false
ErrorTask:
class: ErrorTaskFactory
config:
conditional: false
MinLengthTask:
class: MinLengthTaskFactory
config:
conditional: true
inputs: [input_data]
outputs: [output_data]
TrajOptMotionPlannerTask:
class: TrajOptMotionPlannerTaskFactory
config:
conditional: true
inputs: [output_data]
outputs: [output_data]
format_result_as_input: false
ContactCheckTask_1:
class: DiscreteContactCheckTaskFactory
config:
namespace: DiscreteContactCheckTask
conditional: true
inputs: [output_data]
OMPLMotionPlannerTask:
class: OMPLMotionPlannerTaskFactory
config:
conditional: true
inputs: [input_data]
outputs: [output_data]
format_result_as_input: false
ContactCheckTask_2:
class: DiscreteContactCheckTaskFactory
config:
namespace: DiscreteContactCheckTask
conditional: true
inputs: [output_data]
IterativeSplineParameterizationTask:
class: IterativeSplineParameterizationTaskFactory
config:
conditional: true
inputs: [output_data]
outputs: [output_data]
edges:
- source: MinLengthTask
destinations: [ErrorTask, TrajOptMotionPlannerTask]
- source: TrajOptMotionPlannerTask
destinations: [OMPLMotionPlannerTask, ContactCheckTask_1]
- source: ContactCheckTask_1
destinations: [OMPLMotionPlannerTask, IterativeSplineParameterizationTask]
- source: OMPLMotionPlannerTask
destinations: [ErrorTask, ContactCheckTask_2]
- source: ContactCheckTask_2
destinations: [ErrorTask, IterativeSplineParameterizationTask]
- source: IterativeSplineParameterizationTask
destinations: [ErrorTask, DoneTask]
terminals: [ErrorTask, DoneTask]

Descartes Motion Planner Task
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Expand All @@ -238,6 +338,7 @@ Task for running Descartes motion planner
DescartesMotionPlannerTask:
class: DescartesDMotionPlannerTaskFactory
config:
namespace: DescartesMotionPlannerTask # (optional, defaults to parent yaml key name "DescartesMotionPlannerTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
Expand All @@ -251,6 +352,7 @@ Task for running Descartes motion planner
DescartesMotionPlannerTask:
class: DescartesFMotionPlannerTaskFactory
config:
namespace: DescartesMotionPlannerTask # (optional, defaults to parent yaml key name "DescartesMotionPlannerTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
Expand All @@ -266,6 +368,7 @@ Task for running OMPL motion planner
OMPLMotionPlannerTask:
class: OMPLMotionPlannerTaskFactory
config:
namespace: OMPLMotionPlannerTask # (optional, defaults to parent yaml key name "OMPLMotionPlannerTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
Expand All @@ -281,6 +384,7 @@ Task for running TrajOpt motion planner
TrajOptMotionPlannerTask:
class: TrajOptMotionPlannerTaskFactory
config:
namespace: TrajOptMotionPlannerTask # (optional, defaults to parent yaml key name "TrajOptMotionPlannerTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
Expand All @@ -296,6 +400,7 @@ Task for running TrajOpt Ifopt motion planner
TrajOptIfoptMotionPlannerTask:
class: TrajOptIfoptMotionPlannerTaskFactory
config:
namespace: TrajOptIfoptMotionPlannerTask # (optional, defaults to parent yaml key name "TrajOptIfoptMotionPlannerTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
Expand All @@ -311,6 +416,7 @@ Task for running Simple motion planner
SimpleMotionPlannerTask:
class: SimpleMotionPlannerTaskFactory
config:
namespace: SimpleMotionPlannerTask # (optional, defaults to parent yaml key name "SimpleMotionPlannerTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
Expand All @@ -326,6 +432,7 @@ Perform iterative spline time parameterization
IterativeSplineParameterizationTask:
class: IterativeSplineParameterizationTaskFactory
config:
namespace: IterativeSplineParameterizationTask # (optional, defaults to parent yaml key name "IterativeSplineParameterizationTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
Expand All @@ -341,6 +448,7 @@ Perform time optimal time parameterization
TimeOptimalParameterizationTask:
class: TimeOptimalParameterizationTaskFactory
config:
namespace: TimeOptimalParameterizationTask # (optional, defaults to parent yaml key name "TimeOptimalParameterizationTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
Expand All @@ -355,6 +463,7 @@ Perform trajectory smoothing leveraging Ruckig. Time parameterization must be ra
RuckigTrajectorySmoothingTask:
class: RuckigTrajectorySmoothingTaskFactory
config:
namespace: RuckigTrajectorySmoothingTask # (optional, defaults to parent yaml key name "RuckigTrajectorySmoothingTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
Expand Down Expand Up @@ -421,9 +530,10 @@ Task for checking input data structure

.. code-block:: yaml

MinLengthTask:
class: MinLengthTaskFactory
CheckInputTask:
class: CheckInputTaskFactory
config:
namespace: CheckInputTask # (optional, defaults to parent yaml key name "CheckInputTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
Expand All @@ -438,6 +548,7 @@ Continuous collision check trajectory task
ContinuousContactCheckTask:
class: ContinuousContactCheckTaskFactory
config:
namespace: ContinuousContactCheckTask # (optional, defaults to parent yaml key name "ContinuousContactCheckTask")
conditional: true
inputs: [input_data]

Expand All @@ -451,6 +562,7 @@ Discrete collision check trajectory task
DiscreteContactCheckTask:
class: DiscreteContactCheckTaskFactory
config:
namespace: DiscreteContactCheckTask # (optional, defaults to parent yaml key name "DiscreteContactCheckTask")
conditional: true
inputs: [input_data]

Expand Down Expand Up @@ -516,6 +628,7 @@ This task modifies the input instructions in order to push waypoints that are ou
FixStateBoundsTask:
class: FixStateBoundsTaskFactory
config:
namespace: FixStateBoundsTask # (optional, defaults to parent yaml key name "FixStateBoundsTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
Expand All @@ -533,6 +646,7 @@ This task modifies the input instructions in order to push waypoints that are in
FixStateCollisionTask:
class: FixStateCollisionTaskFactory
config:
namespace: FixStateCollisionTask # (optional, defaults to parent yaml key name "FixStateCollisionTask")
conditional: true
inputs: [input_data]
outputs: [output_data]
Expand All @@ -547,6 +661,7 @@ Task for processing the input data so it meets a minimum length. Planners like t
MinLengthTask:
class: MinLengthTaskFactory
config:
namespace: MinLengthTask # (optional, defaults to parent yaml key name "MinLengthTask")
conditional: false
inputs: [input_data]
outputs: [output_data]
Expand All @@ -561,6 +676,7 @@ This task simply returns a value specified in the composite profile. This can be
ProfileSwitchTask:
class: ProfileSwitchTaskFactory
config:
namespace: ProfileSwitchTask # (optional, defaults to parent yaml key name "ProfileSwitchTask")
conditional: false
inputs: [input_data]

Expand All @@ -577,6 +693,7 @@ This is used to upsample the results trajectory based on the longest valid segme
UpsampleTrajectoryTask:
class: UpsampleTrajectoryTaskFactory
config:
namespace: UpsampleTrajectoryTask # (optional, defaults to parent yaml key name "UpsampleTrajectoryTask")
conditional: false
inputs: [input_data]
outputs: [output_data]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,12 @@ class TaskComposerNode
/** @brief The name of the node */
const std::string& getName() const;

/** @brief Set the namespace of the node */
void setNamespace(const std::string& ns);

/** @brief The namespace of the node */
const std::string& getNamespace() const;

/** @brief The node type TASK, GRAPH, etc */
TaskComposerNodeType getType() const;

Expand Down Expand Up @@ -142,6 +148,9 @@ class TaskComposerNode
/** @brief The name of the task */
std::string name_;

/** @brief The namespace of the task */
std::string ns_;

/** @brief The node type */
TaskComposerNodeType type_;

Expand Down
9 changes: 8 additions & 1 deletion tesseract_task_composer/core/src/task_composer_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ namespace tesseract_planning
{
TaskComposerNode::TaskComposerNode(std::string name, TaskComposerNodeType type, bool conditional)
: name_(std::move(name))
, ns_(name_)
, type_(type)
, uuid_(boost::uuids::random_generator()())
, uuid_str_(boost::uuids::to_string(uuid_))
Expand All @@ -51,6 +52,8 @@ TaskComposerNode::TaskComposerNode(std::string name, TaskComposerNodeType type,
{
try
{
ns_ = config["namespace"].IsDefined() ? config["namespace"].as<std::string>() : name_;
Levi-Armstrong marked this conversation as resolved.
Show resolved Hide resolved

if (YAML::Node n = config["conditional"])
conditional_ = n.as<bool>();

Expand Down Expand Up @@ -79,6 +82,9 @@ TaskComposerNode::TaskComposerNode(std::string name, TaskComposerNodeType type,
void TaskComposerNode::setName(const std::string& name) { name_ = name; }
const std::string& TaskComposerNode::getName() const { return name_; }

void TaskComposerNode::setNamespace(const std::string& ns) { ns_ = ns; }
const std::string& TaskComposerNode::getNamespace() const { return ns_; }

TaskComposerNodeType TaskComposerNode::getType() const { return type_; }

const boost::uuids::uuid& TaskComposerNode::getUUID() const { return uuid_; }
Expand Down Expand Up @@ -134,7 +140,8 @@ std::string TaskComposerNode::dump(std::ostream& os,

if (conditional_)
{
os << std::endl << tmp << " [shape=diamond, label=\"" << name_ << "\\n(" << uuid_str_ << ")";
os << std::endl << tmp << " [shape=diamond, label=\"" << name_ << "\\n";
os << "Namespace: " << ns_ << "\\n(" << uuid_str_ << ")";

os << "\\n Inputs: [";
for (std::size_t i = 0; i < input_keys_.size(); ++i)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class MotionPlannerTask : public TaskComposerTask
bool format_result_as_input,
bool conditional)
: TaskComposerTask(std::move(name), conditional)
, planner_(std::make_shared<MotionPlannerType>(name_))
, planner_(std::make_shared<MotionPlannerType>(ns_))
, format_result_as_input_(format_result_as_input)
{
input_keys_.push_back(std::move(input_key));
Expand All @@ -62,7 +62,7 @@ class MotionPlannerTask : public TaskComposerTask
explicit MotionPlannerTask(std::string name, // NOLINT(performance-unnecessary-value-param)
const YAML::Node& config,
const TaskComposerPluginFactory& /*plugin_factory*/)
: TaskComposerTask(std::move(name), config), planner_(std::make_shared<MotionPlannerType>(name_))
: TaskComposerTask(std::move(name), config), planner_(std::make_shared<MotionPlannerType>(ns_))
{
if (input_keys_.empty())
throw std::runtime_error("MotionPlannerTask, config missing 'inputs' entry");
Expand Down
Loading
Loading