Enumerations | Variables
area_division.h File Reference
#include <ros/ros.h>
#include <map>
#include <vector>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Vector3.h>
#include <nav_msgs/OccupancyGrid.h>
#include <nav_msgs/GetMap.h>
#include <cpswarm_msgs/AreaDivisionEvent.h>
#include <cpswarm_msgs/GetDouble.h>
#include <cpswarm_msgs/ArrayOfStates.h>
#include <cpswarm_msgs/StateEvent.h>
#include <swarmros/String.h>
#include "lib/area_division.h"
Include dependency graph for area_division.h:

Go to the source code of this file.

Enumerations

enum  state_t {
  IDLE = 0, INIT, ACTIVE, SYNC,
  DIVIDE, DEINIT
}
 An enumeration for the state of the division. More...
 

Variables

Publisher area_pub
 Publisher to visualize the assigned area grid map. More...
 
string behavior
 The current behavior state of this CPS. More...
 
bool behavior_valid
 Whether a valid state has been received. More...
 
vector< string > behaviors
 The behavior states in which area division is active. More...
 
area_divisiondivision
 The object encapsulating the area division optimization algorithm. More...
 
Subscriber division_sub
 Subscriber to get area division requests from other CPSs. More...
 
nav_msgs::OccupancyGrid global_map
 The complete grid map. More...
 
Publisher map_ds_pub
 Publisher to visualize the downsampled map. More...
 
Publisher map_rot_pub
 Publisher to visualize the rotated map. More...
 
Subscriber map_sub
 Subscriber to get grid map. More...
 
bool map_valid
 Whether a valid grid map has been received. More...
 
Publisher pos_pub
 Publisher to stop the CPS. More...
 
geometry_msgs::Pose pose
 Current position of the CPS. More...
 
Subscriber pose_sub
 Subscriber to get CPS position. More...
 
bool pose_valid
 Whether a valid position has been received. More...
 
Raterate
 ROS rate object for controlling loop rates. More...
 
double resolution
 The grid map underlying the area division will be downsampled to this resolution in meter / cell. More...
 
ServiceClient rotater_cli
 Service client to get the angle which the area has to be rotated by. More...
 
state_t state
 The state of the area division node. More...
 
map< string, Timeswarm
 The UUIDs of the other swarm members. More...
 
map< string, geometry_msgs::PoseStamped > swarm_pose
 The positions of the other swarm members. More...
 
Publisher swarm_pub
 Publisher to syncronize with other CPSs. More...
 
Subscriber swarm_sub
 Subscriber to get information about other CPSs in the swarm. More...
 
double swarm_timeout
 The time in seconds communication in the swarm can be delayed at most. Used to wait after an area division event before starting the area division or time after which it is assumed that a swarm member has left the swarm if no position update has been received. More...
 
bool swarm_valid
 Whether valid state information has been received from the other swarm members. More...
 
Time sync_start
 The time at which the synchronization for the area division started. More...
 
geometry_msgs::Vector3 translation
 The translation by which the area has been shifted. More...
 
string uuid
 UUID of this CPS. More...
 
Subscriber uuid_sub
 Subscriber to get CPS UUID. More...
 
bool visualize
 Whether to publish the area division on a topic for visualization. More...
 

Enumeration Type Documentation

enum state_t

An enumeration for the state of the division.

Enumerator
IDLE 
INIT 
ACTIVE 
SYNC 
DIVIDE 
DEINIT 

Definition at line 25 of file area_division.h.

Variable Documentation

Publisher area_pub

Publisher to visualize the assigned area grid map.

Definition at line 77 of file area_division.h.

string behavior

The current behavior state of this CPS.

Definition at line 107 of file area_division.h.

bool behavior_valid

Whether a valid state has been received.

Definition at line 112 of file area_division.h.

vector<string> behaviors

The behavior states in which area division is active.

Definition at line 117 of file area_division.h.

area_division* division

The object encapsulating the area division optimization algorithm.

Definition at line 157 of file area_division.h.

Subscriber division_sub

Subscriber to get area division requests from other CPSs.

Definition at line 62 of file area_division.h.

nav_msgs::OccupancyGrid global_map

The complete grid map.

Definition at line 147 of file area_division.h.

Publisher map_ds_pub

Publisher to visualize the downsampled map.

Definition at line 87 of file area_division.h.

Publisher map_rot_pub

Publisher to visualize the rotated map.

Definition at line 82 of file area_division.h.

Subscriber map_sub

Subscriber to get grid map.

Definition at line 57 of file area_division.h.

bool map_valid

Whether a valid grid map has been received.

Definition at line 152 of file area_division.h.

Publisher pos_pub

Publisher to stop the CPS.

Definition at line 67 of file area_division.h.

geometry_msgs::Pose pose

Current position of the CPS.

Definition at line 137 of file area_division.h.

Subscriber pose_sub

Subscriber to get CPS position.

Definition at line 47 of file area_division.h.

bool pose_valid

Whether a valid position has been received.

Definition at line 142 of file area_division.h.

Rate* rate

ROS rate object for controlling loop rates.

Definition at line 97 of file area_division.h.

double resolution

The grid map underlying the area division will be downsampled to this resolution in meter / cell.

Definition at line 167 of file area_division.h.

ServiceClient rotater_cli

Service client to get the angle which the area has to be rotated by.

Definition at line 92 of file area_division.h.

state_t state

The state of the area division node.

Definition at line 37 of file area_division.h.

map<string, Time> swarm

The UUIDs of the other swarm members.

Definition at line 127 of file area_division.h.

map<string, geometry_msgs::PoseStamped> swarm_pose

The positions of the other swarm members.

Definition at line 122 of file area_division.h.

Publisher swarm_pub

Publisher to syncronize with other CPSs.

Definition at line 72 of file area_division.h.

Subscriber swarm_sub

Subscriber to get information about other CPSs in the swarm.

Definition at line 52 of file area_division.h.

double swarm_timeout

The time in seconds communication in the swarm can be delayed at most. Used to wait after an area division event before starting the area division or time after which it is assumed that a swarm member has left the swarm if no position update has been received.

Definition at line 172 of file area_division.h.

bool swarm_valid

Whether valid state information has been received from the other swarm members.

Definition at line 132 of file area_division.h.

Time sync_start

The time at which the synchronization for the area division started.

Definition at line 182 of file area_division.h.

geometry_msgs::Vector3 translation

The translation by which the area has been shifted.

Definition at line 162 of file area_division.h.

string uuid

UUID of this CPS.

Definition at line 102 of file area_division.h.

Subscriber uuid_sub

Subscriber to get CPS UUID.

Definition at line 42 of file area_division.h.

bool visualize

Whether to publish the area division on a topic for visualization.

Definition at line 177 of file area_division.h.



area_division
Author(s): Micha Sende
autogenerated on Tue Jan 19 2021 03:30:02