#include "coverage_path.h"
Go to the source code of this file.
Functions | |
| void | analyze_area (vector< geometry_msgs::Point > coords, geometry_msgs::Point &origin, double &rotation, double &width, double &height) |
| Determine properties of an area. More... | |
| void | area_callback (const nav_msgs::OccupancyGrid::ConstPtr &msg) |
| Callback function to receive the grid map. More... | |
| void | downsample (nav_msgs::OccupancyGrid &map) |
| Decrease the resolution of a occupancy grid map. More... | |
| bool | generate_path (geometry_msgs::Point start) |
| Generate an optimal coverage path for a given area. More... | |
| bool | get_path (nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &res) |
| Callback function to get the coverage path. More... | |
| bool | get_waypoint (cpswarm_msgs::GetWaypoint::Request &req, cpswarm_msgs::GetWaypoint::Response &res) |
| Callback function to get the current waypoint of the path. More... | |
| int | main (int argc, char **argv) |
| A ROS node that computes the optimal paths for area coverage with a swarm of CPSs. More... | |
| void | rotate (nav_msgs::OccupancyGrid &map, double angle) |
| Rotate an occupancy grid map so the lower boundary is horizontal. More... | |
| void | swarm_state_callback (const cpswarm_msgs::ArrayOfStates::ConstPtr &msg) |
| Callback function to receive the states of the other CPSs. More... | |
| void analyze_area | ( | vector< geometry_msgs::Point > | coords, |
| geometry_msgs::Point & | origin, | ||
| double & | rotation, | ||
| double & | width, | ||
| double & | height | ||
| ) |
Determine properties of an area.
| coords | The coordinates defining the area polygon. |
| origin | Returns the bottom left coordinate of the area. |
| rotation | Returns the angle which the area has to be rotated so the lower boundary is horizontal. |
| width | Returns the width of the area after rotation. |
| height | Returns the height of the area after rotation. |
Definition at line 11 of file coverage_path.cpp.
| void area_callback | ( | const nav_msgs::OccupancyGrid::ConstPtr & | msg | ) |
Callback function to receive the grid map.
| msg | Grid map to be covered by this CPSs. |
Definition at line 338 of file coverage_path.cpp.
| void downsample | ( | nav_msgs::OccupancyGrid & | map | ) |
Decrease the resolution of a occupancy grid map.
| map | A reference to the occupancy grid map to downsample. |
Definition at line 148 of file coverage_path.cpp.
| bool generate_path | ( | geometry_msgs::Point | start | ) |
Generate an optimal coverage path for a given area.
| start | The starting position of the path. |
Definition at line 224 of file coverage_path.cpp.
| bool get_path | ( | nav_msgs::GetPlan::Request & | req, |
| nav_msgs::GetPlan::Response & | res | ||
| ) |
Callback function to get the coverage path.
| req | Path planning request that is ignored. |
| res | The coverage path. |
Definition at line 290 of file coverage_path.cpp.
| bool get_waypoint | ( | cpswarm_msgs::GetWaypoint::Request & | req, |
| cpswarm_msgs::GetWaypoint::Response & | res | ||
| ) |
Callback function to get the current waypoint of the path.
| req | Empty get waypoint request. |
| res | The current waypoint. |
Definition at line 310 of file coverage_path.cpp.
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
A ROS node that computes the optimal paths for area coverage with a swarm of CPSs.
| argc | Number of command line arguments. |
| argv | Array of command line arguments. |
Definition at line 397 of file coverage_path.cpp.
| void rotate | ( | nav_msgs::OccupancyGrid & | map, |
| double | angle | ||
| ) |
Rotate an occupancy grid map so the lower boundary is horizontal.
| map | A reference to the occupancy grid map to rotate. |
| angle | The angle to rotate the map by. |
Definition at line 71 of file coverage_path.cpp.
| void swarm_state_callback | ( | const cpswarm_msgs::ArrayOfStates::ConstPtr & | msg | ) |
Callback function to receive the states of the other CPSs.
| msg | UUIDs and states of the other CPSs. |
Definition at line 349 of file coverage_path.cpp.