Given an existing MTC Task object, appends an MTC Stage to the Task that initializes it with the final planning scene of a given solution.
More...
#include <setup_mtc_from_solution.hpp>
Given an existing MTC Task object, appends an MTC Stage to the Task that initializes it with the final planning scene of a given solution.
Data Port Name | Port Type | Object Type |
task | Bidirectional | std::shared_ptr<moveit::task_constructor::Task> |
solution | Input | std::shared_ptr<moveit_task_constructor_msgs::msg::Solution> |
◆ SetupMTCFromSolution()
moveit_studio::behaviors::SetupMTCFromSolution::SetupMTCFromSolution |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config |
|
) |
| |
◆ metadata()
BT::KeyValueVector moveit_studio::behaviors::SetupMTCFromSolution::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
BT::PortsList moveit_studio::behaviors::SetupMTCFromSolution::providedPorts |
( |
| ) |
|
|
static |
◆ tick()
BT::NodeStatus moveit_studio::behaviors::SetupMTCFromSolution::tick |
( |
| ) |
|
|
override |
◆ kDefaultStageName
constexpr auto moveit_studio::behaviors::SetupMTCFromSolution::kDefaultStageName = "initial state" |
|
staticconstexpr |
The documentation for this class was generated from the following files: