Given an existing MTC Task object and a sequence of target poses, appends MTC stages to plan a sequence of cartesian motions between the poses.
More...
#include <setup_mtc_cartesian_sequence.hpp>
|
| SetupMTCCartesianSequence (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
| Constructor for SetupMTCCartesianSequence behavior. More...
|
|
BT::NodeStatus | tick () override |
| Synchronous, blocking function that must return SUCCESS/FAILURE every time this action node is ticked by the behavior tree. More...
|
|
| 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 BT::PortsList | providedPorts () |
| Custom tree nodes that have input and/or output ports must define them in this static function. More...
|
|
static BT::KeyValueVector | metadata () |
|
Given an existing MTC Task object and a sequence of target poses, appends MTC stages to plan a sequence of cartesian motions between the poses.
Data Port Name | Port Type | Object Type |
task | Bidirectional | std::shared_ptr<moveit::task_constructor::Task> |
ik_frame | Input | std::string |
planning_group_name | Input | std::string |
pose_stamped_vector | Input | std::vector<geometry_msgs::msg::PoseStamped> |
monitored_stage | Input | std::string |
◆ SetupMTCCartesianSequence()
moveit_studio::behaviors::SetupMTCCartesianSequence::SetupMTCCartesianSequence |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config, |
|
|
const std::shared_ptr< BehaviorContext > & |
shared_resources |
|
) |
| |
Constructor for SetupMTCCartesianSequence behavior.
- Parameters
-
name | Name of the node. Must match the name used for this node in the behavior tree definition file (the .xml file). |
config | Node configuration. Only used here because the BehaviorTree.CPP expects constructor signature with name and config first before custom constructor parameters. |
shared_resources | Provides access to common resources such as the node handle and failure logger that are shared between all the behaviors that inherit from moveit_studio::behaviors::SharedResourcesNode. |
◆ metadata()
BT::KeyValueVector moveit_studio::behaviors::SetupMTCCartesianSequence::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
BT::PortsList moveit_studio::behaviors::SetupMTCCartesianSequence::providedPorts |
( |
| ) |
|
|
static |
Custom tree nodes that have input and/or output ports must define them in this static function.
This function must be static. It is a requirement set by the BehaviorTree.CPP library.
- Returns
- List of ports with the names and port info. The return value is for the internal use of the behavior tree.
◆ tick()
BT::NodeStatus moveit_studio::behaviors::SetupMTCCartesianSequence::tick |
( |
| ) |
|
|
override |
Synchronous, blocking function that must return SUCCESS/FAILURE every time this action node is ticked by the behavior tree.
- Returns
- Status of the node. Must be either SUCCESS/FAILURE (the node is "complete" for now). Cannot be RUNNING since this is a synchronous node.
Move through a sequence of Cartesian waypoints
Generate Joint State at Pose
The documentation for this class was generated from the following files: