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

Allows or forbids collisions between two entities in the planning scene's Allowed Collision Matrix, without an MTC task. More...

#include <set_collision_rule.hpp>

Inheritance diagram for moveit_pro::behaviors::SetCollisionRule:
Collaboration diagram for moveit_pro::behaviors::SetCollisionRule:

Public Member Functions

 SetCollisionRule (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
 SetCollisionRule (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 kPortIDNameA = "name_a"
 
static constexpr auto kPortIDNameB = "name_b"
 
static constexpr auto kPortIDAllowCollision = "allow_collision"
 
static constexpr auto kPortIDPlanningScene = "planning_scene"
 

Protected Member Functions

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.
 

Additional Inherited Members

- Protected Attributes inherited from moveit_pro::behaviors::SharedResourcesNode< BT::StatefulActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Allows or forbids collisions between two entities in the planning scene's Allowed Collision Matrix, without an MTC task.

Each of name_a and name_b is resolved against planning groups, collision object ids, and robot links (in that order); a planning group expands to its links with collision geometry. The Behavior fails with a descriptive error if a name is ambiguous (matches more than one category) or matches nothing, because a silent no-op is not acceptable for a collision-rule change. Collision rules are symmetric, so the ports are named name_a / name_b rather than directional.

The Behavior has two operating modes selected by the planning_scene port:

  • Live scene mode (port unwired): the Behavior fetches the current scene from /get_planning_scene, updates the ACM, and commits it via /apply_planning_scene. Service names are hard-coded; they are not exposed as ports. This is the default behavior.
  • Supplied scene mode (port wired): the Behavior reads the moveit_msgs::PlanningScene supplied on the port, updates its ACM, and writes the result back to the same port. No service calls are made.
Data Port Name Port Type Object Type
name_a input std::string
name_b input std::string
allow_collision input bool
planning_scene bidirectional moveit_msgs::msg::PlanningScene

Constructor & Destructor Documentation

◆ SetCollisionRule() [1/2]

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

◆ SetCollisionRule() [2/2]

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

Member Function Documentation

◆ doWork()

tl::expected< bool, std::string > moveit_pro::behaviors::SetCollisionRule::doWork ( )
overrideprotectedvirtual

User-implemented function which handles executing the potentially-long-running process.

This function is called within an async process in a separate thread.

Returns
A tl::expected which contains a bool indicating task success if the process completed successfully or was canceled, or an error message if the process failed unexpectedly.

Implements moveit_pro::behaviors::AsyncBehaviorBase.

◆ getFuture()

std::shared_future< tl::expected< bool, std::string > > & moveit_pro::behaviors::SetCollisionRule::getFuture ( )
inlineoverrideprotectedvirtual

Gets the shared future which is used to monitor the progress of the async process.

Classes derived from AsyncBehaviorBase must implement getFuture() so that it returns a shared_future class member.

This exists to prevent destruction of the derived class while the async process is still in-progress. If the derived class is destroyed, the definitions of the functions used within doWork() will be destroyed too, which will result in the virtual functions in the base class being called instead and cause a fault.

This function will force derived classes to add an instance of this type and return a reference to it. The base class can then use this virtual function to access the shared future in functions like onStart.

By adding this virtual function we're properly demonstrating how this future depends on things from the derived class and the natural flow of object lifetimes will do the hard work for us. The std::shared_future destructor will get the value of the future before the derived class is destructed assuming it's the last reference to the shared state. Doing it this way means neither the base nor derived class should need to implement a destructor which is a nice property to have.

Returns
Returns the shared_future, which should be owned by the child class.

Implements moveit_pro::behaviors::AsyncBehaviorBase.

◆ metadata()

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

◆ providedPorts()

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

Member Data Documentation

◆ kPortIDAllowCollision

constexpr auto moveit_pro::behaviors::SetCollisionRule::kPortIDAllowCollision = "allow_collision"
staticconstexpr

◆ kPortIDNameA

constexpr auto moveit_pro::behaviors::SetCollisionRule::kPortIDNameA = "name_a"
staticconstexpr

◆ kPortIDNameB

constexpr auto moveit_pro::behaviors::SetCollisionRule::kPortIDNameB = "name_b"
staticconstexpr

◆ kPortIDPlanningScene

constexpr auto moveit_pro::behaviors::SetCollisionRule::kPortIDPlanningScene = "planning_scene"
staticconstexpr

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