Creates a zig-zag path for a robot end-effector to follow, to cover a given area.
More...
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
| | |
2<---------------<1 |
void registerBehavior(BT::BehaviorTreeFactory &factory, const std::string &name)
Helper function to register a behavior with the default constructor signature with a BT::BehaviorTree...
Definition shared_resources_node_loader.hpp:51
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.