![]() |
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Given an existing MTC Task object, appends an MTC CurrentState Stage to the Task. More...
#include <setup_mtc_current_state.hpp>
Public Member Functions | |
SetupMTCCurrentState (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
BT::NodeStatus | tick () override |
![]() | |
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 () |
Static Public Attributes | |
static constexpr auto | kDefaultStageName = "current state" |
Additional Inherited Members | |
![]() | |
std::shared_ptr< BehaviorContext > | shared_resources_ |
Given an existing MTC Task object, appends an MTC CurrentState Stage to the Task.
Data Port Name | Port Type | Object Type |
---|---|---|
task | Bidirectional | std::shared_ptr<moveit::task_constructor::Task> |
moveit_studio::behaviors::SetupMTCCurrentState::SetupMTCCurrentState | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
|
static |
|
static |
|
override |
|
staticconstexpr |