MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis Class Reference

The SetupMTCMultiEEFMoveAlongAxis class adds a dual cartesian motion stage to a MoveIt Task Constructor task. More...

#include <setup_mtc_multi_eef_cartesian.hpp>

Inheritance diagram for moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis:
Collaboration diagram for moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis:

Public Member Functions

 SetupMTCMultiEEFMoveAlongAxis (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructor.
 
BT::NodeStatus tick () override
 Main execution function for the node.
 
- 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.
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 Provides the list of required and optional ports.
 
static BT::KeyValueVector metadata ()
 Provides metadata for this node.
 

Static Public Attributes

static constexpr auto kPortIdIkFrames = "ik_frames"
 
static constexpr auto kPortIdPlanningGroupNames = "planning_group_names"
 
static constexpr auto kPortIdAxisX = "axis_x"
 
static constexpr auto kPortIdAxisY = "axis_y"
 
static constexpr auto kPortIdAxisZ = "axis_z"
 
static constexpr auto kPortIdMinDistance = "min_distance"
 
static constexpr auto kPortIdMaxDistance = "max_distance"
 
static constexpr auto kPortIdTask = "task"
 
static constexpr auto kPortIdMonitoredStage = "monitored_stage"
 
static constexpr auto kPortIdVelocityScaleFactor = "velocity_scale_factor"
 
static constexpr auto kPortIdAccelerationScaleFactor = "acceleration_scale_factor"
 
static constexpr auto kPortIdKeepOrientation = "keep_orientation"
 

Additional Inherited Members

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

Detailed Description

The SetupMTCMultiEEFMoveAlongAxis class adds a dual cartesian motion stage to a MoveIt Task Constructor task.

This BehaviorTree node retrieves parameters from its input ports and sets up a MoveRelative stage (one for each provided IK frame) whose motions are merged together.

Constructor & Destructor Documentation

◆ SetupMTCMultiEEFMoveAlongAxis()

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

Constructor.

Parameters
nameThe name of the BT node.
configThe node configuration.
shared_resourcesPointer to shared resources, including the robot model.

Member Function Documentation

◆ metadata()

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

Provides metadata for this node.

Returns
A BT::KeyValueVector containing metadata fields such as description and subcategory.

◆ providedPorts()

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

Provides the list of required and optional ports.

Returns
A BT::PortsList containing the definitions of the input and output ports.

◆ tick()

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

Main execution function for the node.

This function retrieves inputs from the BehaviorTree ports, validates them, creates a dual cartesian motion stage, and adds it to the provided MTC task.

Returns
BT::NodeStatus::SUCCESS if the stage was added successfully, otherwise BT::NodeStatus::FAILURE.

Member Data Documentation

◆ kPortIdAccelerationScaleFactor

constexpr auto moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis::kPortIdAccelerationScaleFactor = "acceleration_scale_factor"
staticconstexpr

◆ kPortIdAxisX

constexpr auto moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis::kPortIdAxisX = "axis_x"
staticconstexpr

◆ kPortIdAxisY

constexpr auto moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis::kPortIdAxisY = "axis_y"
staticconstexpr

◆ kPortIdAxisZ

constexpr auto moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis::kPortIdAxisZ = "axis_z"
staticconstexpr

◆ kPortIdIkFrames

constexpr auto moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis::kPortIdIkFrames = "ik_frames"
staticconstexpr

◆ kPortIdKeepOrientation

constexpr auto moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis::kPortIdKeepOrientation = "keep_orientation"
staticconstexpr

◆ kPortIdMaxDistance

constexpr auto moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis::kPortIdMaxDistance = "max_distance"
staticconstexpr

◆ kPortIdMinDistance

constexpr auto moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis::kPortIdMinDistance = "min_distance"
staticconstexpr

◆ kPortIdMonitoredStage

constexpr auto moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis::kPortIdMonitoredStage = "monitored_stage"
staticconstexpr

◆ kPortIdPlanningGroupNames

constexpr auto moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis::kPortIdPlanningGroupNames = "planning_group_names"
staticconstexpr

◆ kPortIdTask

constexpr auto moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis::kPortIdTask = "task"
staticconstexpr

◆ kPortIdVelocityScaleFactor

constexpr auto moveit_studio::behaviors::SetupMTCMultiEEFMoveAlongAxis::kPortIdVelocityScaleFactor = "velocity_scale_factor"
staticconstexpr

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