|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Takes a shared pointer to an existing MTC Task object via an input data port, plans the Task, and sets the solution with the lowest overall cost as an output data port. A service client sends over all the solutions to the MTC Solution Manager node which can be used for debugging. More...
#include <plan_mtc_task.hpp>


Public Member Functions | |
| PlanMTCTask (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
Public Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase | |
| AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| virtual | ~AsyncBehaviorBase ()=default |
| BT::NodeStatus | onStart () override |
| Required implementation of BT::StatefulActionNode::onStart(). | |
| BT::NodeStatus | onRunning () override |
| Required implementation of BT::StatefulActionNode::onRunning(). | |
| void | onHalted () override |
| Required implementation of BT::StatefulActionNode::onHalted(). | |
| void | resetStatus () |
| Resets the internal status of this node. | |
Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| SharedResourcesNode (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| Constructor for SharedResourcesNode. Called by BT::BehaviorTreeFactory when creating a new behavior tree containing this node. | |
Static Public Member Functions | |
| static BT::PortsList | providedPorts () |
| static BT::KeyValueVector | metadata () |
Additional Inherited Members | |
Protected Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase | |
| void | notifyCanHalt () |
| Called when runAsync() finishes to notify onHalted() that the async process has finished. | |
Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| std::shared_ptr< BehaviorContext > | shared_resources_ |
Takes a shared pointer to an existing MTC Task object via an input data port, plans the Task, and sets the solution with the lowest overall cost as an output data port. A service client sends over all the solutions to the MTC Solution Manager node which can be used for debugging.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| task | Input | std::shared_ptr<moveit::task_constructor::Task> |
| solution | Output | moveit_task_constructor_msgs::msg::Solution |
| moveit_studio::behaviors::PlanMTCTask::PlanMTCTask | ( | const std::string & | name, |
| const BT::NodeConfiguration & | config, | ||
| const std::shared_ptr< BehaviorContext > & | shared_resources | ||
| ) |
|
static |
|
static |