|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
This Behavior sends a request to add a tool to the planning scene as a collision object. More...
#include <add_tool.hpp>


Public Member Functions | |
| AddTool (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| AddTool (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< AddURDFSrv > > client_interface) | |
Public Member Functions inherited from moveit_studio::behaviors::AddURDF | |
| AddURDF (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| AddURDF (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< AddURDFSrv > > client_interface) | |
Public Member Functions inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< moveit_studio_agent_msgs::srv::AddURDF > | |
| 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::AddURDF > > 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::AddURDF | |
| static BT::PortsList | providedPorts () |
| static BT::KeyValueVector | metadata () |
Static Public Attributes | |
| static constexpr auto | kToolNamePort = "tool_name" |
| static constexpr auto | kPackageNamePort = "package_name" |
| static constexpr auto | kToolUrdfFilePort = "tool_urdf_file_path" |
| static constexpr auto | kToolPosePort = "relative_pose" |
Static Public Attributes inherited from moveit_studio::behaviors::AddURDF | |
| static constexpr auto | kDefaultUrdfNamePort = "urdf_name" |
| static constexpr auto | kDefaultPackageNamePort = "package_name" |
| static constexpr auto | kDefaultUrdfFilePathPort = "urdf_file_path" |
| static constexpr auto | kDefaultUrdfPosePort = "urdf_pose" |
| static constexpr auto | kColorNamePort = "urdf_color" |
Static Public Attributes inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< moveit_studio_agent_msgs::srv::AddURDF > | |
| static constexpr std::chrono::seconds | kTimeoutWaitForServiceServer |
Protected Member Functions | |
| std::string | getUrdfNamePort () const override |
| std::string | getPackageNamePort () const override |
| std::string | getUrdfFilePathPort () const override |
| std::string | getUrdfPosePort () const override |
Protected Member Functions inherited from moveit_studio::behaviors::AddURDF | |
| virtual std::string | getColorPort () const |
Protected Member Functions inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< moveit_studio_agent_msgs::srv::AddURDF > | |
| 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::AddURDF | |
| using | AddURDFSrv = moveit_studio_agent_msgs::srv::AddURDF |
Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| std::shared_ptr< BehaviorContext > | shared_resources_ |
This Behavior sends a request to add a tool to the planning scene as a collision object.
The tool is added to the planning scene at the specified pose. The tool is given as a URDF file, which describes the kinematics and collision geometry.
See also AttachTool for attaching a tool.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| tool_name | input | std::string |
| package_name | input | std::string |
| tool_urdf_file | input | std::string |
| tool_pose | input | geometry_msgs::msg::PoseStamped |
|
explicit |
|
explicit |
|
inlineoverrideprotectedvirtual |
Reimplemented from moveit_studio::behaviors::AddURDF.
|
inlineoverrideprotectedvirtual |
Reimplemented from moveit_studio::behaviors::AddURDF.
|
inlineoverrideprotectedvirtual |
Reimplemented from moveit_studio::behaviors::AddURDF.
|
inlineoverrideprotectedvirtual |
Reimplemented from moveit_studio::behaviors::AddURDF.
|
static |
|
static |
|
staticconstexpr |