MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::GenerateCoveragePath Class Referencefinal

Creates a zig-zag path for a robot end-effector to follow, to cover a given area. More...

#include <generate_coverage_path.hpp>

Inheritance diagram for moveit_studio::behaviors::GenerateCoveragePath:
Collaboration diagram for moveit_studio::behaviors::GenerateCoveragePath:

Public Member Functions

 GenerateCoveragePath (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
BT::NodeStatus tick () override
 
- Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode >
 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. More...
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 
static BT::KeyValueVector metadata ()
 

Static Public Attributes

static constexpr auto kBottomRightCornerPortID = "bottom_right_corner"
 
static constexpr auto kWidthPortID = "width"
 
static constexpr auto kHeightPortID = "height"
 
static constexpr auto kStrideDistancePortID = "stride_distance"
 
static constexpr auto kVectorOfPosesPortID = "vector_of_poses"
 

Additional Inherited Members

- Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Creates a zig-zag path for a robot end-effector to follow, to cover a given area.

Data Port Name Port Type Object Type
bottom_right_corner Input geometry_msgs::msg::PoseStamped
width Input double
height Input double
stride_distance Input double
vector_of_poses Output std::vector<geometry_msgs::msg::PoseStamped>

The zig-zag path is generated by starting at the bottom right corner of the area, moving to the bottom left corner, then moving up the stride distance, back to the right, and so on until the top left corner is reached. As an example, this a path with 8 waypoints (numbered 1 to 8):

7>--------------->8
| |
| |
6<-- - - - - - - <5
| |
| |
3> - - - - - - -->4
| | ^ y
| | |
2<---------------<1 |
<----x bottom_right_corner
x

It is assumed the frame of the bottom_right_corner pose is defined as shown in the diagram above, i.e. X pointing to the right, Y pointing up, and Z pointing into the page. The path is generated by moving along the x-axis first, then the y-axis. The width and height parameters define the size of the area to be covered, and the stride_distance parameter defines the distance between each zig-zag path, all dimensions given in meters.

If the stride distance doesn't add up exactly to the height, the last stride won't be included, i.e. the actual area covered will be less than the given height.

The path is returned as a vector of PoseStamped messages, in the same frame as the given bottom_right_corner pose.

Constructor & Destructor Documentation

◆ GenerateCoveragePath()

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

Member Function Documentation

◆ metadata()

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

◆ providedPorts()

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

◆ tick()

BT::NodeStatus moveit_studio::behaviors::GenerateCoveragePath::tick ( )
override

Member Data Documentation

◆ kBottomRightCornerPortID

constexpr auto moveit_studio::behaviors::GenerateCoveragePath::kBottomRightCornerPortID = "bottom_right_corner"
staticconstexpr

◆ kHeightPortID

constexpr auto moveit_studio::behaviors::GenerateCoveragePath::kHeightPortID = "height"
staticconstexpr

◆ kStrideDistancePortID

constexpr auto moveit_studio::behaviors::GenerateCoveragePath::kStrideDistancePortID = "stride_distance"
staticconstexpr

◆ kVectorOfPosesPortID

constexpr auto moveit_studio::behaviors::GenerateCoveragePath::kVectorOfPosesPortID = "vector_of_poses"
staticconstexpr

◆ kWidthPortID

constexpr auto moveit_studio::behaviors::GenerateCoveragePath::kWidthPortID = "width"
staticconstexpr

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