MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behaviors::SetupMTCPlanToJointState Class Referencefinal

Given an existing MTC Task object and a joint state, appends MTC stages to describe a freespace motion plan to that joint state using the MoveIt Pro RRTConnect planner. More...

#include <setup_mtc_plan_to_joint_state.hpp>

Inheritance diagram for moveit_studio::behaviors::SetupMTCPlanToJointState:
Collaboration diagram for moveit_studio::behaviors::SetupMTCPlanToJointState:

Public Member Functions

 SetupMTCPlanToJointState (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.
 

Static Public Member Functions

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

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 and a joint state, appends MTC stages to describe a freespace motion plan to that joint state using the MoveIt Pro RRTConnect planner.

Data Port Name Port Type Object Type
planning_group_name Input std::string
joint_state Input moveit_studio_agent_msgs::msg::RobotJointState
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
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>

Constructor & Destructor Documentation

◆ SetupMTCPlanToJointState()

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

Member Function Documentation

◆ metadata()

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

◆ providedPorts()

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

◆ tick()

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

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