Given an existing MTC Task object and a target pose, appends MTC stages to describe a freespace motion plan to that target pose using the MoveIt Pro RRTConnect Planner.
More...
#include <setup_mtc_plan_to_pose.hpp>
|
static BT::PortsList | providedPorts () |
| Custom tree nodes that have input and/or output ports must define them in this static function.
|
|
static BT::KeyValueVector | metadata () |
|
Given an existing MTC Task object and a target pose, appends MTC stages to describe a freespace motion plan to that target pose using the MoveIt Pro RRTConnect Planner.
Data Port Name | Port Type | Object Type |
grasp_link | Input | std::string |
target_pose | Input | geometry_msgs::msg::PoseStamped |
monitored_stage | Input | std::string |
velocity_scale_factor | Input | double |
acceleration_scale_factor | Input | double |
max_iterations | Input | unsigned int |
trajectory_sampling_rate | Input | unsigned int |
link_padding | Input | double |
planning_group_name | Input | std::string |
keep_orientation | Input | bool |
keep_orientation_tolerance | Input | double |
keep_orientation_link_names | Input | std::vector<std::string> |
task | Bidirectional | std::shared_ptr<moveit::task_constructor::Task> |
◆ SetupMTCPlanToPose()
moveit_studio::behaviors::SetupMTCPlanToPose::SetupMTCPlanToPose |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config, |
|
|
const std::shared_ptr< BehaviorContext > & |
shared_resources |
|
) |
| |
Constructor for GetLatestTransform 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::SetupMTCPlanToPose::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
BT::PortsList moveit_studio::behaviors::SetupMTCPlanToPose::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::SetupMTCPlanToPose::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.
The documentation for this class was generated from the following files: