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>
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 |
| seed | Input | int |
| keep_orientation | Input | bool |
| keep_orientation_tolerance | Input | double |
| keep_orientation_link_names | Input | std::vector<std::string> |
| task | Bidirectional | std::shared_ptr<moveit_pro::task_constructor::Task> |
◆ SetupMTCPlanToJointState()
| moveit_pro::behaviors::SetupMTCPlanToJointState::SetupMTCPlanToJointState |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config, |
|
|
const std::shared_ptr< BehaviorContext > & |
shared_resources |
|
) |
| |
◆ metadata()
| BT::KeyValueVector moveit_pro::behaviors::SetupMTCPlanToJointState::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
| BT::PortsList moveit_pro::behaviors::SetupMTCPlanToJointState::providedPorts |
( |
| ) |
|
|
static |
◆ tick()
| BT::NodeStatus moveit_pro::behaviors::SetupMTCPlanToJointState::tick |
( |
| ) |
|
|
override |
◆ kDefaultStageName
The documentation for this class was generated from the following files: