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::World * | world |
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::Pose > | base_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::Pose > | initial_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 |
Definition at line 67 of file stageros.cpp.
StageNode::StageNode | ( | int | argc, |
char ** | argv, | ||
bool | gui, | ||
const char * | fname, | ||
bool | use_model_names | ||
) |
Definition at line 274 of file stageros.cpp.
StageNode::~StageNode | ( | ) |
Definition at line 402 of file stageros.cpp.
bool StageNode::cb_reset_srv | ( | std_srvs::Empty::Request & | request, |
std_srvs::Empty::Response & | response | ||
) |
Definition at line 252 of file stageros.cpp.
void StageNode::cmdvelReceived | ( | int | idx, |
const boost::shared_ptr< geometry_msgs::Twist const > & | msg | ||
) |
Definition at line 265 of file stageros.cpp.
|
staticprivate |
Definition at line 230 of file stageros.cpp.
|
private |
Definition at line 174 of file stageros.cpp.
|
private |
Definition at line 200 of file stageros.cpp.
|
inlinestaticprivate |
Definition at line 117 of file stageros.cpp.
int StageNode::SubscribeModels | ( | ) |
Definition at line 324 of file stageros.cpp.
bool StageNode::UpdateWorld | ( | ) |
Definition at line 409 of file stageros.cpp.
void StageNode::WorldCallback | ( | ) |
Definition at line 415 of file stageros.cpp.
|
private |
Definition at line 133 of file stageros.cpp.
|
private |
Definition at line 142 of file stageros.cpp.
|
private |
Definition at line 140 of file stageros.cpp.
|
private |
Definition at line 134 of file stageros.cpp.
|
private |
Definition at line 78 of file stageros.cpp.
|
private |
Definition at line 108 of file stageros.cpp.
|
private |
Definition at line 105 of file stageros.cpp.
|
private |
Definition at line 110 of file stageros.cpp.
|
private |
Definition at line 79 of file stageros.cpp.
|
private |
Definition at line 75 of file stageros.cpp.
|
private |
Definition at line 72 of file stageros.cpp.
|
private |
Definition at line 80 of file stageros.cpp.
|
private |
Definition at line 106 of file stageros.cpp.
|
private |
Definition at line 102 of file stageros.cpp.
|
private |
Definition at line 137 of file stageros.cpp.
|
private |
Definition at line 130 of file stageros.cpp.
|
private |
Definition at line 111 of file stageros.cpp.
Stg::World* StageNode::world |
Definition at line 169 of file stageros.cpp.