|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Attaches a collision object that is already in the planning scene to a robot link. More...
#include <attach_object.hpp>


Public Member Functions | |
| AttachObject (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| AttachObject (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< PlanningSceneBridge > bridge) | |
| ~AttachObject () override=default | |
Public Member Functions inherited from moveit_pro::behaviors::AsyncBehaviorBase | |
| AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| ~AsyncBehaviorBase () override=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_pro::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 Attributes | |
| static constexpr auto | kPortIDObjectId = "object_id" |
| static constexpr auto | kPortIDLinkName = "link_name" |
| static constexpr auto | kPortIDAllowedCollisionLinks = "allowed_collision_links" |
| static constexpr auto | kPortIDRelativeTransform = "relative_transform" |
| static constexpr auto | kPortIDPlanningScene = "planning_scene" |
Additional Inherited Members | |
Protected Member Functions inherited from moveit_pro::behaviors::AsyncBehaviorBase | |
| virtual tl::expected< void, std::string > | doHalt () |
| Optionally implement additional work needed to cleanly interrupt the async process. | |
| void | notifyCanHalt () |
| Called when runAsync() finishes to notify onHalted() that the async process has finished. | |
Protected Attributes inherited from moveit_pro::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| std::shared_ptr< BehaviorContext > | shared_resources_ |
Attaches a collision object that is already in the planning scene to a robot link.
Works for collision objects in the world. For URDF objects, use AttachURDF instead.
The Behavior has two operating modes selected by the planning_scene input port:
/get_planning_scene service, then commits an attach diff via the /apply_planning_scene service. The server moves the object from the world to the requested link, reusing the object's existing geometry. Service names are hard-coded; they are not exposed as ports.moveit_msgs::PlanningScene message supplied on the port, moves the matching entry from world.collision_objects into robot_state.attached_collision_objects with the requested link and allowed collision links, and writes the modified scene back to the same port. No service calls are made.By default the object keeps its current pose relative to the link. Wire the optional relative_transform port to instead attach the object at a chosen transform link_T_object, regardless of where the object currently is. When relative_transform is wired and the id is already attached to link_name, the object is re-posed to the requested transform (and its allowed collision links are refreshed from allowed_collision_links) rather than treated as a no-op.
Succeeds without changes (no-op) when the id is already attached to link_name and no relative_transform is requested: the attachment intent is already satisfied. Fails when object_id or link_name is empty, when the id is absent from the scene, or when the id is attached to a different link.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| object_id | input | std::string |
| link_name | input | std::string |
| allowed_collision_links | input | std::vector<std::string> |
| relative_transform | input | geometry_msgs::msg::Transform |
| planning_scene | bidirectional | moveit_msgs::msg::PlanningScene |
|
explicit |
|
explicit |
|
overridedefault |
|
static |
|
static |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |