StageNode Class Reference

List of all members.

Public Member Functions

 StageNode (int argc, char **argv, bool gui, const char *fname)
int SubscribeModels ()
bool UpdateWorld ()
void WorldCallback ()
 ~StageNode ()

Public Attributes

Stg::World * world

Private Member Functions

const char * mapName (const std::string name, size_t robotID)
const char * mapName (const char *name, size_t robotID)

Static Private Member Functions

static void ghfunc (Stg::Model *mod, StageNode *node)
static bool s_update (Stg::World *world, StageNode *node)

Private Attributes

ros::Publisher clock_pub_
Clock clockMsg
std::vector< ros::Publisher > laser_pubs_
std::vector< Stg::ModelLaser * > lasermodels
sensor_msgs::LaserScan * laserMsgs
boost::mutex msg_lock
ros::NodeHandle n_
std::vector< Stg::ModelPosition * > positionmodels
ros::Time sim_time
tf::TransformBroadcaster tf
std::vector< ArtVehicleModel * > vehicleModels_

Detailed Description

Definition at line 80 of file artstage.cc.


Constructor & Destructor Documentation

StageNode::StageNode ( int  argc,
char **  argv,
bool  gui,
const char *  fname 
)

Todo:
support more than one simulated robot

Definition at line 178 of file artstage.cc.

StageNode::~StageNode (  ) 

Definition at line 282 of file artstage.cc.


Member Function Documentation

void StageNode::ghfunc ( Stg::Model *  mod,
StageNode node 
) [static, private]

Definition at line 162 of file artstage.cc.

const char* StageNode::mapName ( const std::string  name,
size_t  robotID 
) [inline, private]

Definition at line 117 of file artstage.cc.

const char * StageNode::mapName ( const char *  name,
size_t  robotID 
) [private]

Definition at line 149 of file artstage.cc.

static bool StageNode::s_update ( Stg::World *  world,
StageNode node 
) [inline, static, private]

Definition at line 106 of file artstage.cc.

int StageNode::SubscribeModels (  ) 

Definition at line 246 of file artstage.cc.

bool StageNode::UpdateWorld (  ) 

Definition at line 290 of file artstage.cc.

void StageNode::WorldCallback (  ) 

Definition at line 296 of file artstage.cc.


Member Data Documentation

ros::Publisher StageNode::clock_pub_ [private]

Definition at line 97 of file artstage.cc.

Definition at line 85 of file artstage.cc.

std::vector<ros::Publisher> StageNode::laser_pubs_ [private]

Definition at line 96 of file artstage.cc.

std::vector<Stg::ModelLaser *> StageNode::lasermodels [private]

Definition at line 94 of file artstage.cc.

sensor_msgs::LaserScan* StageNode::laserMsgs [private]

Definition at line 84 of file artstage.cc.

boost::mutex StageNode::msg_lock [private]

Definition at line 91 of file artstage.cc.

ros::NodeHandle StageNode::n_ [private]

Definition at line 88 of file artstage.cc.

std::vector<Stg::ModelPosition *> StageNode::positionmodels [private]

Definition at line 95 of file artstage.cc.

ros::Time StageNode::sim_time [private]

Definition at line 123 of file artstage.cc.

tf::TransformBroadcaster StageNode::tf [private]

Definition at line 120 of file artstage.cc.

std::vector<ArtVehicleModel *> StageNode::vehicleModels_ [private]

Definition at line 100 of file artstage.cc.

Stg::World* StageNode::world

Definition at line 144 of file artstage.cc.


The documentation for this class was generated from the following file:
 All Classes Files Functions Variables Typedefs Defines


simulator_art
Author(s): Jack O'Quin
autogenerated on Fri Jan 11 09:57:49 2013