Classes | Public Member Functions | Public Attributes | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
StageNode Class Reference

Classes

struct  StageRobot
 

Public Member Functions

bool cb_reset_srv (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 
void cmdvelReceived (int idx, const boost::shared_ptr< geometry_msgs::Twist const > &msg)
 
 StageNode (int argc, char **argv, bool gui, const char *fname, bool use_model_names)
 
int SubscribeModels ()
 
bool UpdateWorld ()
 
void WorldCallback ()
 
 ~StageNode ()
 

Public Attributes

Stg::Worldworld
 

Private Member Functions

const char * mapName (const char *name, size_t robotID, Stg::Model *mod) const
 
const char * mapName (const char *name, size_t robotID, size_t deviceID, Stg::Model *mod) const
 

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
 
std::vector< Stg::Posebase_last_globalpos
 
ros::Time base_last_globalpos_time
 
ros::Duration base_watchdog_timeout
 
std::vector< Stg::ModelCamera * > cameramodels
 
ros::Publisher clock_pub_
 
std::vector< Stg::Poseinitial_poses
 
bool isDepthCanonical
 
std::vector< Stg::ModelRanger * > lasermodels
 
boost::mutex msg_lock
 
ros::NodeHandle n_
 
std::vector< Stg::ModelPosition * > positionmodels
 
ros::ServiceServer reset_srv_
 
std::vector< StageRobot const * > robotmodels_
 
ros::Time sim_time
 
tf::TransformBroadcaster tf
 
bool use_model_names
 

Detailed Description

Definition at line 66 of file stageros.cpp.

Constructor & Destructor Documentation

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

Definition at line 269 of file stageros.cpp.

StageNode::~StageNode ( )

Definition at line 393 of file stageros.cpp.

Member Function Documentation

bool StageNode::cb_reset_srv ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)

Definition at line 247 of file stageros.cpp.

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

Definition at line 260 of file stageros.cpp.

void StageNode::ghfunc ( Stg::Model mod,
StageNode node 
)
staticprivate

Definition at line 229 of file stageros.cpp.

const char * StageNode::mapName ( const char *  name,
size_t  robotID,
Stg::Model mod 
) const
private

Definition at line 173 of file stageros.cpp.

const char * StageNode::mapName ( const char *  name,
size_t  robotID,
size_t  deviceID,
Stg::Model mod 
) const
private

Definition at line 199 of file stageros.cpp.

static bool StageNode::s_update ( Stg::World world,
StageNode node 
)
inlinestaticprivate

Definition at line 116 of file stageros.cpp.

int StageNode::SubscribeModels ( )

Definition at line 323 of file stageros.cpp.

bool StageNode::UpdateWorld ( )

Definition at line 400 of file stageros.cpp.

void StageNode::WorldCallback ( )

Definition at line 406 of file stageros.cpp.

Member Data Documentation

ros::Time StageNode::base_last_cmd
private

Definition at line 132 of file stageros.cpp.

std::vector<Stg::Pose> StageNode::base_last_globalpos
private

Definition at line 141 of file stageros.cpp.

ros::Time StageNode::base_last_globalpos_time
private

Definition at line 139 of file stageros.cpp.

ros::Duration StageNode::base_watchdog_timeout
private

Definition at line 133 of file stageros.cpp.

std::vector<Stg::ModelCamera *> StageNode::cameramodels
private

Definition at line 77 of file stageros.cpp.

ros::Publisher StageNode::clock_pub_
private

Definition at line 107 of file stageros.cpp.

std::vector<Stg::Pose> StageNode::initial_poses
private

Definition at line 104 of file stageros.cpp.

bool StageNode::isDepthCanonical
private

Definition at line 109 of file stageros.cpp.

std::vector<Stg::ModelRanger *> StageNode::lasermodels
private

Definition at line 78 of file stageros.cpp.

boost::mutex StageNode::msg_lock
private

Definition at line 74 of file stageros.cpp.

ros::NodeHandle StageNode::n_
private

Definition at line 71 of file stageros.cpp.

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

Definition at line 79 of file stageros.cpp.

ros::ServiceServer StageNode::reset_srv_
private

Definition at line 105 of file stageros.cpp.

std::vector<StageRobot const *> StageNode::robotmodels_
private

Definition at line 101 of file stageros.cpp.

ros::Time StageNode::sim_time
private

Definition at line 136 of file stageros.cpp.

tf::TransformBroadcaster StageNode::tf
private

Definition at line 129 of file stageros.cpp.

bool StageNode::use_model_names
private

Definition at line 110 of file stageros.cpp.

Stg::World* StageNode::world

Definition at line 168 of file stageros.cpp.


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


stage_ros
Author(s): Brian Gerky
autogenerated on Sat Apr 24 2021 02:23:34