MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behaviors::AddVirtualObjectToPlanningScene Class Referencefinal

Uses the service provided by the ApplyPlanningScene MoveGroup capability plugin to add a virtual collision object to the planning scene. A virtual collision object can collide with other 'virtual' objects in the planning scene, but not with the robot links, or any other objects that are considered not virtual, e.g. added via AddURDF or ModifyObjectInPlanningScene. More...

#include <add_virtual_object_to_planning_scene.hpp>

Inheritance diagram for moveit_studio::behaviors::AddVirtualObjectToPlanningScene:
Collaboration diagram for moveit_studio::behaviors::AddVirtualObjectToPlanningScene:

Public Member Functions

 AddVirtualObjectToPlanningScene (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructor for the AddVirtualObjectToPlanningScene behavior.
 
 AddVirtualObjectToPlanningScene (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< ApplyPlanningScene > > client_interface)
 
- Public Member Functions inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< ApplyPlanningScene >
 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< ApplyPlanningScene > > 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 ()
 

Additional Inherited Members

- Static Public Attributes inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< ApplyPlanningScene >
static constexpr std::chrono::seconds kTimeoutWaitForServiceServer
 
- Protected Member Functions inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< ApplyPlanningScene >
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.
 
- Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Uses the service provided by the ApplyPlanningScene MoveGroup capability plugin to add a virtual collision object to the planning scene. A virtual collision object can collide with other 'virtual' objects in the planning scene, but not with the robot links, or any other objects that are considered not virtual, e.g. added via AddURDF or ModifyObjectInPlanningScene.

Data Port Name Port Type Object Type
object Input moveit_studio_vision_msgs::msg::GraspableObject
planning_scene_msg Input moveit_msgs::msg::PlanningScene
apply_planning_scene_service Input std::string

Constructor & Destructor Documentation

◆ AddVirtualObjectToPlanningScene() [1/2]

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

Constructor for the AddVirtualObjectToPlanningScene behavior.

Parameters
nameSee SharedResourcesNode
configSee SharedResourcesNode
shared_resourcesSee SharedResourcesNode

◆ AddVirtualObjectToPlanningScene() [2/2]

moveit_studio::behaviors::AddVirtualObjectToPlanningScene::AddVirtualObjectToPlanningScene ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources,
std::unique_ptr< ClientInterfaceBase< ApplyPlanningScene > >  client_interface 
)
explicit

Member Function Documentation

◆ metadata()

BT::KeyValueVector moveit_studio::behaviors::AddVirtualObjectToPlanningScene::metadata ( )
static

◆ providedPorts()

BT::PortsList moveit_studio::behaviors::AddVirtualObjectToPlanningScene::providedPorts ( )
static

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