MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::SetupMTCCurrentState Class Referencefinal

Given an existing MTC Task object, appends an MTC CurrentState Stage to the Task. More...

#include <setup_mtc_current_state.hpp>

Inheritance diagram for moveit_studio::behaviors::SetupMTCCurrentState:
Collaboration diagram for moveit_studio::behaviors::SetupMTCCurrentState:

Public Member Functions

 SetupMTCCurrentState (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
BT::NodeStatus tick () override
 
- Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode >
 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. More...
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 
static BT::KeyValueVector metadata ()
 

Static Public Attributes

static constexpr auto kDefaultStageName = "current state"
 

Additional Inherited Members

- Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

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>
skip_collision_check Input bool

By default, this stage will check for collisions between any two objects in the planning scene. If any collisions are found, the stage will fail, and the colliding bodies will be returned in the error message. Adding this check to the generator stage is the fastest way to have an MTC task fail when the input is in collision.

The collision check can be skipped by setting skip_collision_check to true.

Constructor & Destructor Documentation

◆ SetupMTCCurrentState()

moveit_studio::behaviors::SetupMTCCurrentState::SetupMTCCurrentState ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources 
)

Member Function Documentation

◆ metadata()

BT::KeyValueVector moveit_studio::behaviors::SetupMTCCurrentState::metadata ( )
static

◆ providedPorts()

BT::PortsList moveit_studio::behaviors::SetupMTCCurrentState::providedPorts ( )
static

◆ tick()

BT::NodeStatus moveit_studio::behaviors::SetupMTCCurrentState::tick ( )
override

Member Data Documentation

◆ kDefaultStageName

constexpr auto moveit_studio::behaviors::SetupMTCCurrentState::kDefaultStageName = "current state"
staticconstexpr

The documentation for this class was generated from the following files: