This Behavior sends a request to attach a tool to a robot for motion planning purposes.
More...
|
| AttachTool (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
|
| AttachTool (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< AttachToolSrv >> client_interface) |
|
| ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
| Constructs ServiceClientBehaviorBase using the RclcppClientInterface. More...
|
|
| ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< moveit_studio_agent_msgs::srv::AttachTool >> client_interface) |
| Constructs ServiceClientBehaviorBase using a user-provided implementation of ClientInterfaceBase. More...
|
|
virtual | ~ServiceClientBehaviorBase ()=default |
|
| AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
|
virtual | ~AsyncBehaviorBase ()=default |
|
BT::NodeStatus | onStart () override |
| Required implementation of BT::StatefulActionNode::onStart(). More...
|
|
BT::NodeStatus | onRunning () override |
| Required implementation of BT::StatefulActionNode::onRunning(). More...
|
|
void | onHalted () override |
| Required implementation of BT::StatefulActionNode::onHalted(). More...
|
|
void | resetStatus () |
| Resets the internal status of this node. 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...
|
|
This Behavior sends a request to attach a tool to a robot for motion planning purposes.
The tool must first be added to the planning scene before it can be attached. It is attached to the robot at the specified link at the relative pose between the link and the tool collision object. Once attached, the tool will move with the link it is attached to. If the tool contains joints and those are reported in the /joint_states topic, the tool collision shapes will update their state accordingly. If the tool is allowed to collide with some other links (e.g. the link it is attached to), these links can be specified in the allowed_collision_links
port.
See also DetachTool for detaching a tool.
Data Port Name | Port Type | Object Type |
tool_name | input | std::string |
parent_link_name | input | std::string |
allowed_collision_links | input | std::vector<std::string> |