|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Updates the reference pose of an existing CollisionObject in the planning scene. More...
#include <move_collision_object.hpp>


Public Member Functions | |
| MoveCollisionObject (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| MoveCollisionObject (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< PlanningSceneBridge > bridge) | |
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 | 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_ |
Updates the reference pose of an existing CollisionObject in the planning scene.
Replaces the remove-and-re-add workaround for repositioning collision objects. The Behavior emits a CollisionObject::MOVE so all child shapes (primitives, meshes, planes) follow the new reference pose without any per-shape pose updates and without a transient gap in collision checking.
The Behavior has two operating modes selected by the planning_scene input port:
/get_planning_scene service to verify the object exists and is not currently attached, then commits a MOVE diff to the /apply_planning_scene service. Service names are hard-coded; they are not exposed as ports. The new pose may be in any frame — the planning scene resolves it via TF.world.collision_objects, updates its pose field in place, and writes the modified scene back to the same port. No service calls are made. The supplied pose must be in the same frame as the existing entry's header.frame_id; the Behavior fails otherwise, because mutating the reference pose without transforming the shape poses would leave the entry self-inconsistent.Returns FAILURE when object_id is empty, when pose.header.frame_id is empty, when no world entry with the given id exists, when an entry with the same id is currently attached to the robot (MOVE for attached objects is not supported; the caller must detach first), when the supplied scene's matching entry is in a different frame than the input pose, or when a required service call fails in live scene mode.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| object_id | input | std::string |
| pose | input | geometry_msgs::msg::PoseStamped |
| planning_scene | bidirectional | moveit_msgs::msg::PlanningScene |
|
explicit |
|
explicit |
|
static |
|
static |
|
staticconstexpr |