MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_pro::behaviors::AddCollisionBox Class Referencefinal

Adds a box-shaped CollisionObject to the planning scene. More...

#include <add_collision_box.hpp>

Inheritance diagram for moveit_pro::behaviors::AddCollisionBox:
Collaboration diagram for moveit_pro::behaviors::AddCollisionBox:

Public Member Functions

 AddCollisionBox (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
 AddCollisionBox (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::AddCollisionObjectBase
 AddCollisionObjectBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
 AddCollisionObjectBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< PlanningSceneBridge > bridge)
 
 ~AddCollisionObjectBase () 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 Member Functions inherited from moveit_pro::behaviors::AddCollisionObjectBase
static BT::PortsList commonPorts ()
 Returns the input ports owned by this base class: overwrite and planning_scene. Subclasses concatenate this list into their own providedPorts() so every shape-specific Add inherits the same wiring.
 

Additional Inherited Members

- Static Public Attributes inherited from moveit_pro::behaviors::AddCollisionObjectBase
static constexpr auto kPortIDOverwrite = "overwrite"
 
static constexpr auto kPortIDPlanningScene = "planning_scene"
 
- Protected Member Functions inherited from moveit_pro::behaviors::AddCollisionObjectBase
tl::expected< bool, std::string > doWork () override
 User-implemented function which handles executing the potentially-long-running process.
 
std::shared_future< tl::expected< bool, std::string > > & getFuture () override
 Gets the shared future which is used to monitor the progress of the async process.
 
- 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< BehaviorContextshared_resources_
 

Detailed Description

Adds a box-shaped CollisionObject to the planning scene.

Reads object_id, dimensions, and pose from the input ports and builds a box-shaped CollisionObject (one SOLID_PRIMITIVE BOX), then adds it to a planning scene. By default the Behavior modifies the live planning scene via service calls. Wire the planning_scene port to modify a supplied moveit_msgs::msg::PlanningScene message instead; the modified scene is written back to the same port and no services are called. See AddCollisionObjectBase for details on the two modes and the overwrite port semantics.

Returns FAILURE when object_id is empty, when dimensions.size() is not 3, when any element of dimensions is non-finite or not greater than 0, when pose.header.frame_id is empty, when overwrite=false and a world entry with the same id is already present, when an entry with the same id is currently attached to the robot, or when a required service call fails in live scene mode.

Data Port Name Port Type Object Type
object_id input std::string
dimensions input std::vector<double>
pose input geometry_msgs::msg::PoseStamped
overwrite input bool
planning_scene bidirectional moveit_msgs::msg::PlanningScene

Constructor & Destructor Documentation

◆ AddCollisionBox() [1/2]

moveit_pro::behaviors::AddCollisionBox::AddCollisionBox ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources 
)
explicit

◆ AddCollisionBox() [2/2]

moveit_pro::behaviors::AddCollisionBox::AddCollisionBox ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources,
std::unique_ptr< PlanningSceneBridge bridge 
)
explicit

Member Function Documentation

◆ metadata()

BT::KeyValueVector moveit_pro::behaviors::AddCollisionBox::metadata ( )
static

◆ providedPorts()

BT::PortsList moveit_pro::behaviors::AddCollisionBox::providedPorts ( )
static

The documentation for this class was generated from the following files: