|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Removes a collision object from a planning scene by id. More...
#include <remove_collision_object.hpp>


Public Member Functions | |
| RemoveCollisionObject (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| RemoveCollisionObject (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< PlanningSceneBridge > bridge) | |
| ~RemoveCollisionObject () 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 | 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_ |
Removes a collision object from a planning scene by id.
The Behavior has two operating modes selected by the planning_scene input port:
/get_planning_scene service, validates that the id is in the world and is not attached, then commits a REMOVE diff via the /apply_planning_scene service. Service names are hard-coded; they are not exposed as ports.moveit_msgs::PlanningScene message supplied on the port, validates the id against that scene, erases the matching entry from world.collision_objects, and writes the modified scene back to the same port. No service calls are made.Succeeds without changes (no-op) when the id is not present in world.collision_objects: the removal intent is already satisfied. Fails when object_id is empty, or when the id is currently in robot_state.attached_collision_objects. Attached objects must be detached first; the underlying REMOVE operation only affects the world list, so removing an attached id would silently no-op without this check.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| object_id | input | std::string |
| planning_scene | bidirectional | moveit_msgs::msg::PlanningScene |
|
explicit |
|
explicit |
|
overridedefault |
|
static |
|
static |
|
staticconstexpr |
|
staticconstexpr |