Given an existing MTC Task object, appends an MTC FixedState Stage to the Task.
More...
#include <setup_mtc_fixed_joint_state.hpp>
Given an existing MTC Task object, appends an MTC FixedState Stage to the Task.
| Data Port Name | Port Type | Object Type |
| planning_scene_msg | input | moveit_msgs::msg::PlanningScene |
| joint_state_msg | input | sensor_msgs::msg::JointState |
| ignore_collisions | input | bool |
| task | Bidirectional | std::shared_ptr<moveit_pro::task_constructor::Task> |
◆ SetupMTCFixedJointState()
| moveit_pro::behaviors::SetupMTCFixedJointState::SetupMTCFixedJointState |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config |
|
) |
| |
◆ metadata()
| BT::KeyValueVector moveit_pro::behaviors::SetupMTCFixedJointState::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
| BT::PortsList moveit_pro::behaviors::SetupMTCFixedJointState::providedPorts |
( |
| ) |
|
|
static |
◆ tick()
| BT::NodeStatus moveit_pro::behaviors::SetupMTCFixedJointState::tick |
( |
| ) |
|
|
override |
Creates a FixedState MTC stage using the provided input data and appends it to the MTC task.
- Returns
- BT::NodeStatus::SUCCESS if the FixedState stage was created and added to the task.
-
BT::NodeStatus::FAILURE if any input port could not be retrieved.
-
BT::NodeStatus::FAILURE if the provided planning scene message could not be used to set the FixedState stage's planning scene.
-
BT::NodeStatus::FAILURE if the planning scene's robot state could not be set to match the provided joint state.
◆ kDefaultStageName
| constexpr auto moveit_pro::behaviors::SetupMTCFixedJointState::kDefaultStageName = "fixed state" |
|
staticconstexpr |
The documentation for this class was generated from the following files: