|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
This Behavior sends a request to attach a tool to a robot for motion planning purposes. More...
#include <attach_tool.hpp>


Public Member Functions | |
| 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< AttachURDFSrv > > client_interface) | |
Public Member Functions inherited from moveit_studio::behaviors::AttachURDF | |
| AttachURDF (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| AttachURDF (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< AttachURDFSrv > > client_interface) | |
Public Member Functions inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< moveit_studio_agent_msgs::srv::AttachURDF > | |
| ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| Constructs ServiceClientBehaviorBase using the RclcppClientInterface. | |
| 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::AttachURDF > > client_interface) | |
| Constructs ServiceClientBehaviorBase using a user-provided implementation of ClientInterfaceBase. | |
| virtual | ~ServiceClientBehaviorBase ()=default |
Public Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase | |
| 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(). | |
| BT::NodeStatus | onRunning () override |
| Required implementation of BT::StatefulActionNode::onRunning(). | |
| void | onHalted () override |
| Required implementation of BT::StatefulActionNode::onHalted(). | |
| void | resetStatus () |
| Resets the internal status of this node. | |
Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| 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 () |
Static Public Member Functions inherited from moveit_studio::behaviors::AttachURDF | |
| static BT::PortsList | providedPorts () |
| static BT::KeyValueVector | metadata () |
Static Public Attributes | |
| static constexpr auto | kToolNamePort = "tool_name" |
| static constexpr auto | kParentLinkNamePort = "parent_link_name" |
| static constexpr auto | kAllowedCollisionLinksPort = "allowed_collision_links" |
Static Public Attributes inherited from moveit_studio::behaviors::AttachURDF | |
| static constexpr auto | kDefaultUrdfNamePort = "urdf_name" |
| static constexpr auto | kDefaultParentLinkNamePort = "parent_link_name" |
| static constexpr auto | kDefaultAllowedCollisionLinksPort = "allowed_collision_links" |
Static Public Attributes inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< moveit_studio_agent_msgs::srv::AttachURDF > | |
| static constexpr std::chrono::seconds | kTimeoutWaitForServiceServer |
Protected Member Functions | |
| std::string | getUrdfNamePort () const override |
| std::string | getParentLinkNamePort () const override |
| std::string | getAllowedCollisionLinksPort () const override |
Protected Member Functions inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< moveit_studio_agent_msgs::srv::AttachURDF > | |
| virtual tl::expected< std::chrono::duration< double >, std::string > | getWaitForServerAvailableTimeout () |
| Optional user-provided function to set the timeout used when waiting for the service server to be available. | |
| virtual tl::expected< bool, std::string > | processResponse (const typename ServiceT::Response &) |
| Optional user-provided function to process the service response after the service has finished. | |
| tl::expected< void, std::string > | doHalt () override |
| Handles halting logic which is specific to the service client behavior implementation. | |
Protected Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase | |
| void | notifyCanHalt () |
| Called when runAsync() finishes to notify onHalted() that the async process has finished. | |
Additional Inherited Members | |
Public Types inherited from moveit_studio::behaviors::AttachURDF | |
| using | AttachURDFSrv = moveit_studio_agent_msgs::srv::AttachURDF |
Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| std::shared_ptr< BehaviorContext > | shared_resources_ |
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> |
|
explicit |
|
explicit |
|
inlineoverrideprotectedvirtual |
Reimplemented from moveit_studio::behaviors::AttachURDF.
|
inlineoverrideprotectedvirtual |
Reimplemented from moveit_studio::behaviors::AttachURDF.
|
inlineoverrideprotectedvirtual |
Reimplemented from moveit_studio::behaviors::AttachURDF.
|
static |
|
static |
|
staticconstexpr |
|
staticconstexpr |