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

Modifies a coverage path to route around obstacle points using semicircular detours. More...

#include <avoid_points_in_coverage_path.hpp>

Inheritance diagram for moveit_pro::behaviors::AvoidPointsInCoveragePath:
Collaboration diagram for moveit_pro::behaviors::AvoidPointsInCoveragePath:

Public Member Functions

 AvoidPointsInCoveragePath (const std::string &name, const BT::NodeConfiguration &config)
 Constructor.
 
BT::NodeStatus tick () override
 Execute the behavior: modify the coverage path to avoid obstacle points.
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 Declare input and output ports.
 
static BT::KeyValueVector metadata ()
 Provide metadata for the MoveIt Studio Developer Tool UI.
 

Detailed Description

Modifies a coverage path to route around obstacle points using semicircular detours.

For each obstacle point that falls within the boustrophedon spacing of the path, the behavior inserts a semicircular detour on the opposite side of the path from the obstacle. Points that fall within the avoidance radius of an obstacle are removed from the output path and replaced by the arc.

Data Port Name Port Type Object Type
coverage_path input std::vector<geometry_msgs::msg::PoseStamped>
points_to_avoid input std::vector<geometry_msgs::msg::PoseStamped>
stride_spacing input double
avoidance_radius input double
loop_segments input int
modified_path output std::vector<geometry_msgs::msg::PoseStamped>

Constructor & Destructor Documentation

◆ AvoidPointsInCoveragePath()

moveit_pro::behaviors::AvoidPointsInCoveragePath::AvoidPointsInCoveragePath ( const std::string &  name,
const BT::NodeConfiguration &  config 
)

Constructor.

Parameters
nameThe name of a particular instance of this Behavior.
configRuntime configuration for this Behavior, including port mappings.

Member Function Documentation

◆ metadata()

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

Provide metadata for the MoveIt Studio Developer Tool UI.

Returns
A BT::KeyValueVector containing the Behavior metadata.

◆ providedPorts()

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

Declare input and output ports.

Returns
The list of ports for this behavior.

◆ tick()

BT::NodeStatus moveit_pro::behaviors::AvoidPointsInCoveragePath::tick ( )
override

Execute the behavior: modify the coverage path to avoid obstacle points.

Returns
SUCCESS after producing the modified path, FAILURE if required ports are missing.

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