Public Member Functions | Private Attributes
micros_swarm::RuntimeHandle Class Reference

#include <runtime_handle.h>

List of all members.

Public Member Functions

bool checkNeighborsOverlap (int robot_id)
void clearNeighbors ()
void createBlackBoard (int id)
void createVirtualStigmergy (int id)
void deleteBlackBoard (int id)
void deleteBlackBoardValue (int id, const std::string &key)
void deleteListenerHelper (const std::string &key)
void deleteNeighbor (int robot_id)
void deleteNeighborSwarm (int robot_id)
void deleteSwarm (int swarm_id)
void deleteVirtualStigmergy (int id)
void deleteVirtualStigmergyValue (int id, const std::string &key)
int getBarrierSize ()
int getBlackBoardSize (int id)
void getBlackBoardTuple (int id, const std::string &key, BlackBoardTuple &bb_tuple)
const boost::shared_ptr
< ListenerHelper
getListenerHelper (const std::string &key)
bool getNeighborBase (int robot_id, NeighborBase &nb)
const float & getNeighborDistance ()
void getNeighbors (std::map< int, NeighborBase > &neighbors)
std::map< int, NeighborBasegetNeighbors ()
int getNeighborSize ()
const BasegetRobotBase ()
int getRobotID ()
int getRobotStatus ()
int getRobotType ()
bool getSCDSPSOValue (const std::string &aKey, SCDSPSODataTuple &aT)
bool getSwarmFlag (int swarm_id)
void getSwarmList (std::vector< int > &swarm_list)
void getSwarmMembers (int swarm_id, std::set< int > &swarm_members)
int getVirtualStigmergySize (int id)
bool getVirtualStigmergyTuple (int id, const std::string &key, VirtualStigmergyTuple &vstig_tuple)
bool inNeighbors (int robot_id)
bool inNeighborSwarm (int robot_id, int swarm_id)
void insertBarrier (int robot_id)
void insertOrRefreshNeighborSwarm (int robot_id, const std::vector< int > &swarm_list)
void insertOrUpdateBlackBoard (int id, const std::string &key, const std::vector< uint8_t > &value, const ros::Time &timestamp, int robot_id)
void insertOrUpdateListenerHelper (const std::string &key, const boost::shared_ptr< ListenerHelper > helper)
void insertOrUpdateNeighbor (int robot_id, float distance, float azimuth, float elevation, float x, float y, float z, float vx, float vy, float vz)
void insertOrUpdateSCDSPSOValue (const std::string &aKey, const SCDSPSODataTuple &aT)
void insertOrUpdateSwarm (int swarm_id, bool value)
void insertOrUpdateVirtualStigmergy (int id, const std::string &key, const std::vector< uint8_t > &value, unsigned int lclock, time_t wtime, unsigned int rcount, int robot_id)
bool isBlackBoardTupleExist (int id, const std::string &key)
bool isVirtualStigmergyTupleExist (int id, const std::string &key)
void joinNeighborSwarm (int robot_id, int swarm_id)
void leaveNeighborSwarm (int robot_id, int swarm_id)
void printBlackBoard ()
void printNeighbor ()
void printNeighborSwarm ()
void printRobotBase ()
void printSwarm ()
void printVirtualStigmergy ()
 RuntimeHandle ()
void setNeighborDistance (float neighbor_distance)
void setRobotBase (const Base &robot_base)
void setRobotID (int robot_id)
void setRobotStatus (int robot_status)
void setRobotType (int robot_type)
void updateVirtualStigmergyTupleReadCount (int id, const std::string &key, int count)

Private Attributes

std::set< int > barrier_
boost::shared_mutex barrier_mutex_
boost::shared_mutex base_mutex_
boost::shared_mutex bb_mutex_
std::map< int, std::map
< std::string, BlackBoardTuple > > 
blackboard_
boost::shared_ptr
< CheckNeighborInterface
cni_
boost::shared_mutex id_mutex_
std::map< std::string,
boost::shared_ptr
< ListenerHelper > > 
listener_helpers_
boost::shared_mutex listener_helpers_mutex_
float neighbor_distance_
boost::shared_mutex neighbor_distance_mutex_
boost::shared_mutex neighbor_mutex_
boost::shared_mutex neighbor_swarm_mutex_
std::map< int, NeighborSwarmTupleneighbor_swarms_
std::map< int, NeighborBaseneighbors_
Base robot_base_
int robot_id_
int robot_status_
int robot_type_
std::map< std::string,
SCDSPSODataTuple
scds_pso_tuple_
boost::shared_mutex scds_pso_tuple_mutex_
boost::shared_mutex status_mutex_
boost::shared_mutex swarm_mutex_
std::map< int, bool > swarms_
boost::shared_mutex type_mutex_
std::map< int, std::map
< std::string,
VirtualStigmergyTuple > > 
virtual_stigmergy_
boost::shared_mutex vstig_mutex_

Detailed Description

Definition at line 39 of file runtime_handle.h.


Constructor & Destructor Documentation

Definition at line 27 of file runtime_handle.cpp.


Member Function Documentation

Definition at line 516 of file runtime_handle.cpp.

Definition at line 120 of file runtime_handle.cpp.

Definition at line 540 of file runtime_handle.cpp.

Definition at line 366 of file runtime_handle.cpp.

Definition at line 621 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::deleteBlackBoardValue ( int  id,
const std::string &  key 
)

Definition at line 627 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::deleteListenerHelper ( const std::string &  key)

Definition at line 712 of file runtime_handle.cpp.

Definition at line 158 of file runtime_handle.cpp.

Definition at line 345 of file runtime_handle.cpp.

Definition at line 228 of file runtime_handle.cpp.

Definition at line 470 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::deleteVirtualStigmergyValue ( int  id,
const std::string &  key 
)

Definition at line 476 of file runtime_handle.cpp.

Definition at line 724 of file runtime_handle.cpp.

Definition at line 608 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::getBlackBoardTuple ( int  id,
const std::string &  key,
BlackBoardTuple bb_tuple 
)

Definition at line 595 of file runtime_handle.cpp.

const boost::shared_ptr< ListenerHelper > micros_swarm::RuntimeHandle::getListenerHelper ( const std::string &  key)

Definition at line 698 of file runtime_handle.cpp.

Definition at line 107 of file runtime_handle.cpp.

Definition at line 667 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::getNeighbors ( std::map< int, NeighborBase > &  neighbors)

Definition at line 101 of file runtime_handle.cpp.

Definition at line 129 of file runtime_handle.cpp.

Definition at line 135 of file runtime_handle.cpp.

Definition at line 78 of file runtime_handle.cpp.

Definition at line 42 of file runtime_handle.cpp.

Definition at line 66 of file runtime_handle.cpp.

Definition at line 54 of file runtime_handle.cpp.

bool micros_swarm::RuntimeHandle::getSCDSPSOValue ( const std::string &  aKey,
SCDSPSODataTuple aT 
)

Definition at line 730 of file runtime_handle.cpp.

Definition at line 204 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::getSwarmList ( std::vector< int > &  swarm_list)

Definition at line 216 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::getSwarmMembers ( int  swarm_id,
std::set< int > &  swarm_members 
)

Definition at line 330 of file runtime_handle.cpp.

Definition at line 458 of file runtime_handle.cpp.

bool micros_swarm::RuntimeHandle::getVirtualStigmergyTuple ( int  id,
const std::string &  key,
VirtualStigmergyTuple vstig_tuple 
)

Definition at line 421 of file runtime_handle.cpp.

Definition at line 164 of file runtime_handle.cpp.

bool micros_swarm::RuntimeHandle::inNeighborSwarm ( int  robot_id,
int  swarm_id 
)

Definition at line 245 of file runtime_handle.cpp.

Definition at line 718 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::insertOrRefreshNeighborSwarm ( int  robot_id,
const std::vector< int > &  swarm_list 
)

Definition at line 312 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::insertOrUpdateBlackBoard ( int  id,
const std::string &  key,
const std::vector< uint8_t > &  value,
const ros::Time timestamp,
int  robot_id 
)

Definition at line 556 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::insertOrUpdateListenerHelper ( const std::string &  key,
const boost::shared_ptr< ListenerHelper helper 
)

Definition at line 682 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::insertOrUpdateNeighbor ( int  robot_id,
float  distance,
float  azimuth,
float  elevation,
float  x,
float  y,
float  z,
float  vx,
float  vy,
float  vz 
)

Definition at line 141 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::insertOrUpdateSCDSPSOValue ( const std::string &  aKey,
const SCDSPSODataTuple aT 
)

Definition at line 741 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::insertOrUpdateSwarm ( int  swarm_id,
bool  value 
)

Definition at line 189 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::insertOrUpdateVirtualStigmergy ( int  id,
const std::string &  key,
const std::vector< uint8_t > &  value,
unsigned int  lclock,
time_t  wtime,
unsigned int  rcount,
int  robot_id 
)

Definition at line 381 of file runtime_handle.cpp.

bool micros_swarm::RuntimeHandle::isBlackBoardTupleExist ( int  id,
const std::string &  key 
)

Definition at line 581 of file runtime_handle.cpp.

bool micros_swarm::RuntimeHandle::isVirtualStigmergyTupleExist ( int  id,
const std::string &  key 
)

Definition at line 407 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::joinNeighborSwarm ( int  robot_id,
int  swarm_id 
)

Definition at line 263 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::leaveNeighborSwarm ( int  robot_id,
int  swarm_id 
)

Definition at line 290 of file runtime_handle.cpp.

Definition at line 648 of file runtime_handle.cpp.

Definition at line 176 of file runtime_handle.cpp.

Definition at line 351 of file runtime_handle.cpp.

Definition at line 93 of file runtime_handle.cpp.

Definition at line 234 of file runtime_handle.cpp.

Definition at line 496 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::setNeighborDistance ( float  neighbor_distance)

Definition at line 673 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::setRobotBase ( const Base robot_base)

Definition at line 84 of file runtime_handle.cpp.

Definition at line 48 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::setRobotStatus ( int  robot_status)

Definition at line 72 of file runtime_handle.cpp.

Definition at line 60 of file runtime_handle.cpp.

void micros_swarm::RuntimeHandle::updateVirtualStigmergyTupleReadCount ( int  id,
const std::string &  key,
int  count 
)

Definition at line 436 of file runtime_handle.cpp.


Member Data Documentation

Definition at line 142 of file runtime_handle.h.

boost::shared_mutex micros_swarm::RuntimeHandle::barrier_mutex_ [private]

Definition at line 143 of file runtime_handle.h.

boost::shared_mutex micros_swarm::RuntimeHandle::base_mutex_ [private]

Definition at line 127 of file runtime_handle.h.

boost::shared_mutex micros_swarm::RuntimeHandle::bb_mutex_ [private]

Definition at line 137 of file runtime_handle.h.

std::map<int, std::map<std::string, BlackBoardTuple> > micros_swarm::RuntimeHandle::blackboard_ [private]

Definition at line 136 of file runtime_handle.h.

Definition at line 146 of file runtime_handle.h.

boost::shared_mutex micros_swarm::RuntimeHandle::id_mutex_ [private]

Definition at line 121 of file runtime_handle.h.

std::map<std::string, boost::shared_ptr<ListenerHelper> > micros_swarm::RuntimeHandle::listener_helpers_ [private]

Definition at line 140 of file runtime_handle.h.

Definition at line 141 of file runtime_handle.h.

Definition at line 138 of file runtime_handle.h.

Definition at line 139 of file runtime_handle.h.

boost::shared_mutex micros_swarm::RuntimeHandle::neighbor_mutex_ [private]

Definition at line 129 of file runtime_handle.h.

Definition at line 133 of file runtime_handle.h.

Definition at line 132 of file runtime_handle.h.

Definition at line 128 of file runtime_handle.h.

Definition at line 126 of file runtime_handle.h.

Definition at line 120 of file runtime_handle.h.

Definition at line 124 of file runtime_handle.h.

Definition at line 122 of file runtime_handle.h.

Definition at line 144 of file runtime_handle.h.

Definition at line 145 of file runtime_handle.h.

boost::shared_mutex micros_swarm::RuntimeHandle::status_mutex_ [private]

Definition at line 125 of file runtime_handle.h.

boost::shared_mutex micros_swarm::RuntimeHandle::swarm_mutex_ [private]

Definition at line 131 of file runtime_handle.h.

std::map<int, bool> micros_swarm::RuntimeHandle::swarms_ [private]

Definition at line 130 of file runtime_handle.h.

boost::shared_mutex micros_swarm::RuntimeHandle::type_mutex_ [private]

Definition at line 123 of file runtime_handle.h.

std::map<int, std::map<std::string, VirtualStigmergyTuple> > micros_swarm::RuntimeHandle::virtual_stigmergy_ [private]

Definition at line 134 of file runtime_handle.h.

boost::shared_mutex micros_swarm::RuntimeHandle::vstig_mutex_ [private]

Definition at line 135 of file runtime_handle.h.


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


micros_swarm
Author(s):
autogenerated on Thu Jun 6 2019 18:52:14