StageNode Class Reference

List of all members.

Public Member Functions

void cmdvelReceived (int idx, const boost::shared_ptr< geometry_msgs::Twist const > &msg)
 StageNode (int argc, char **argv, bool gui, const char *fname)
int SubscribeModels ()
bool UpdateWorld ()
void WorldCallback ()
 ~StageNode ()

Public Attributes

Stg::Worldworld

Private Member Functions

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::Time base_last_cmd
ros::Duration base_watchdog_timeout
ros::Publisher clock_pub_
rosgraph_msgs::Clock clockMsg
std::vector< ros::Subscriber > cmdvel_subs_
std::vector< ros::Publisher > ground_truth_pubs_
nav_msgs::Odometry * groundTruthMsgs
std::vector< ros::Publisher > laser_pubs_
std::vector< Stg::ModelLaser * > lasermodels
sensor_msgs::LaserScan * laserMsgs
boost::mutex msg_lock
ros::NodeHandle n_
std::vector< ros::Publisher > odom_pubs_
nav_msgs::Odometry * odomMsgs
std::vector< Stg::ModelPosition * > positionmodels
ros::Time sim_time
tf::TransformBroadcaster tf

Detailed Description

Definition at line 58 of file stageros.cpp.


Constructor & Destructor Documentation

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

Definition at line 165 of file stageros.cpp.

StageNode::~StageNode (  ) 

Definition at line 259 of file stageros.cpp.


Member Function Documentation

void StageNode::cmdvelReceived ( int  idx,
const boost::shared_ptr< geometry_msgs::Twist const > &  msg 
)

Definition at line 156 of file stageros.cpp.

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

Definition at line 147 of file stageros.cpp.

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

Definition at line 134 of file stageros.cpp.

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

Definition at line 86 of file stageros.cpp.

int StageNode::SubscribeModels (  ) 

Definition at line 226 of file stageros.cpp.

bool StageNode::UpdateWorld (  ) 

Definition at line 267 of file stageros.cpp.

void StageNode::WorldCallback (  ) 

Definition at line 273 of file stageros.cpp.


Member Data Documentation

ros::Time StageNode::base_last_cmd [private]

Definition at line 101 of file stageros.cpp.

ros::Duration StageNode::base_watchdog_timeout [private]

Definition at line 102 of file stageros.cpp.

ros::Publisher StageNode::clock_pub_ [private]

Definition at line 80 of file stageros.cpp.

rosgraph_msgs::Clock StageNode::clockMsg [private]

Definition at line 65 of file stageros.cpp.

std::vector<ros::Subscriber> StageNode::cmdvel_subs_ [private]

Definition at line 79 of file stageros.cpp.

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

Definition at line 78 of file stageros.cpp.

nav_msgs::Odometry* StageNode::groundTruthMsgs [private]

Definition at line 64 of file stageros.cpp.

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

Definition at line 76 of file stageros.cpp.

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

Definition at line 74 of file stageros.cpp.

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

Definition at line 62 of file stageros.cpp.

boost::mutex StageNode::msg_lock [private]

Definition at line 71 of file stageros.cpp.

ros::NodeHandle StageNode::n_ [private]

Definition at line 68 of file stageros.cpp.

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

Definition at line 77 of file stageros.cpp.

nav_msgs::Odometry* StageNode::odomMsgs [private]

Definition at line 63 of file stageros.cpp.

Definition at line 75 of file stageros.cpp.

ros::Time StageNode::sim_time [private]

Definition at line 105 of file stageros.cpp.

tf::TransformBroadcaster StageNode::tf [private]

Definition at line 98 of file stageros.cpp.

Definition at line 129 of file stageros.cpp.


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


stage
Author(s): Richard Vaughan, with contributions from many others. See web page for a full credits list.
autogenerated on Fri Jan 11 10:03:38 2013