Model class More...
#include <stage.hh>
Classes | |
class | cb_t |
class | Flag |
class | GuiState |
class | RasterVis |
class | TrailItem |
class | Visibility |
Public Types | |
enum | callback_type_t { CB_FLAGDECR, CB_FLAGINCR, CB_GEOM, CB_INIT, CB_LOAD, CB_PARENT, CB_POSE, CB_SAVE, CB_SHUTDOWN, CB_STARTUP, CB_UPDATE, CB_VELOCITY, __CB_TYPE_COUNT } |
Public Member Functions | |
Block * | AddBlockRect (meters_t x, meters_t y, meters_t dx, meters_t dy, meters_t dz) |
void | AddCallback (callback_type_t type, model_callback_t cb, void *user) |
void | AddFlag (Flag *flag) |
void | AddToPose (const Pose &pose) |
void | AddToPose (double dx, double dy, double dz, double da) |
void | AddVisualizer (Visualizer *custom_visual, bool on_by_default) |
void | BecomeParentOf (Model *child) |
int | CallCallbacks (callback_type_t type) |
void | ClearBlocks () |
bool | DataIsFresh () const |
void | Disable () |
void | Enable () |
PowerPack * | FindPowerPack () const |
Model * | GetChild (const std::string &name) const |
Color | GetColor () const |
usec_t | GetEnergyInterval () const |
int | GetFiducialReturn () const |
unsigned int | GetFlagCount () const |
Geom | GetGeom () const |
Pose | GetGlobalPose () const |
Velocity | GetGlobalVelocity () const |
uint32_t | GetId () const |
usec_t | GetInterval () |
kg_t | GetMassOfChildren () const |
const std::string & | GetModelType () const |
Pose | GetPose () const |
std::string | GetSayString () |
unsigned int | GetSubscriptionCount () const |
kg_t | GetTotalMass () const |
Model * | GetUnsubscribedModelOfType (const std::string &type) const |
Model * | GetUnusedModelOfType (const std::string &type) |
usec_t | GetUpdateInterval () const |
World * | GetWorld () const |
Pose | GlobalToLocal (const Pose &pose) const |
bool | HasSubscribers () const |
void | InitControllers () |
bool | IsAntecedent (const Model *testmod) const |
bool | IsDescendent (const Model *testmod) const |
bool | IsRelated (const Model *testmod) const |
void | Load (Worldfile *wf, int wf_entity) |
virtual void | Load () |
void | LoadBlock (Worldfile *wf, int entity) |
void | LoadControllerModule (const char *lib) |
Pose | LocalToGlobal (const Pose &pose) const |
point_t | LocalToGlobal (const point_t &pt) const |
std::vector< point_int_t > | LocalToPixels (const std::vector< point_t > &local) const |
Model (World *world, Model *parent=NULL, const std::string &type="model", const std::string &name="") | |
Model () | |
void | NeedRedraw () |
Model * | Parent () const |
void | PlaceInFreeSpace (meters_t xmin, meters_t xmax, meters_t ymin, meters_t ymax) |
virtual void | PopColor () |
Flag * | PopFlag () |
std::string | PoseString () |
virtual void | Print (char *prefix) const |
virtual const char * | PrintWithPose () const |
virtual void | PushColor (Color col) |
virtual void | PushColor (double r, double g, double b, double a) |
void | PushFlag (Flag *flag) |
void | Rasterize (uint8_t *data, unsigned int width, unsigned int height, meters_t cellwidth, meters_t cellheight) |
void | Redraw () |
int | RemoveCallback (callback_type_t type, model_callback_t callback) |
void | RemoveFlag (Flag *flag) |
void | RemoveVisualizer (Visualizer *custom_visual) |
Model * | Root () |
virtual void | Save () |
void | Say (const std::string &str) |
void | SetBlobReturn (bool val) |
void | SetBoundary (bool val) |
void | SetColor (Color col) |
void | SetFiducialKey (int key) |
void | SetFiducialReturn (int fid) |
void | SetFriction (double friction) |
void | SetGeom (const Geom &src) |
void | SetGlobalPose (const Pose &gpose) |
void | SetGlobalVelocity (const Velocity &gvel) |
void | SetGravityReturn (bool val) |
void | SetGripperReturn (bool val) |
void | SetGuiGrid (bool val) |
void | SetGuiMove (bool val) |
void | SetGuiNose (bool val) |
void | SetGuiOutline (bool val) |
void | SetMapResolution (meters_t res) |
void | SetMass (kg_t mass) |
void | SetObstacleReturn (bool val) |
int | SetParent (Model *newparent) |
void | SetPose (const Pose &pose) |
void | SetRangerReturn (double val) |
void | SetRangerReturn (bool val) |
void | SetStall (bool stall) |
void | SetStickyReturn (bool val) |
virtual void | SetToken (const std::string &str) |
void | SetWatts (watts_t watts) |
void | SetWorldfile (Worldfile *wf, int wf_entity) |
bool | Stalled () const |
void | Subscribe () |
void | Unsubscribe () |
virtual | ~Model () |
Static Public Member Functions | |
static Model * | LookupId (uint32_t id) |
Public Attributes | |
class Stg::Model::Visibility | vis |
Static Public Attributes | |
static std::map< std::string, creator_t > | name_map |
Protected Member Functions | |
void | AppendTouchingModels (std::set< Model * > &touchers) |
void | CallUpdateCallbacks (void) |
void | CommitTestedPose () |
virtual void | DataVisualize (Camera *cam) |
void | DataVisualizeTree (Camera *cam) |
virtual void | DrawBlocks () |
void | DrawBlocksTree () |
void | DrawBoundingBox () |
void | DrawBoundingBoxTree () |
void | DrawFlagList () |
void | DrawGrid () |
void | DrawImage (uint32_t texture_id, Camera *cam, float alpha, double width=1.0, double height=1.0) |
void | DrawOrigin () |
void | DrawOriginTree () |
virtual void | DrawPicker () |
void | DrawPose (Pose pose) |
virtual void | DrawSelected (void) |
virtual void | DrawStatus (Camera *cam) |
void | DrawStatusTree (Camera *cam) |
void | DrawTrailArrows () |
void | DrawTrailBlocks () |
void | DrawTrailFootprint () |
void | Map (unsigned int layer) |
void | Map () |
void | MapFromRoot (unsigned int layer) |
void | MapWithChildren (unsigned int layer) |
meters_t | ModelHeight () const |
void | PopCoords () |
void | PushLocalCoords () |
RaytraceResult | Raytrace (const Pose &pose, const meters_t range, const ray_test_func_t func, const void *arg, const bool ztest=true) |
void | Raytrace (const Pose &pose, const meters_t range, const radians_t fov, const ray_test_func_t func, const void *arg, RaytraceResult *samples, const uint32_t sample_count, const bool ztest=true) |
RaytraceResult | Raytrace (const radians_t bearing, const meters_t range, const ray_test_func_t func, const void *arg, const bool ztest=true) |
void | Raytrace (const radians_t bearing, const meters_t range, const radians_t fov, const ray_test_func_t func, const void *arg, RaytraceResult *samples, const uint32_t sample_count, const bool ztest=true) |
void | RegisterOption (Option *opt) |
virtual void | Shutdown () |
virtual void | Startup () |
Model * | TestCollision () |
void | UnMap (unsigned int layer) |
void | UnMap () |
void | UnMapFromRoot (unsigned int layer) |
void | UnMapWithChildren (unsigned int layer) |
virtual void | Update () |
virtual void | UpdateCharge () |
void | UpdateTrail () |
Static Protected Member Functions | |
static int | UpdateWrapper (Model *mod, void *arg) |
Protected Attributes | |
bool | alwayson |
BlockGroup | blockgroup |
int | blocks_dl |
int | boundary |
std::vector< std::set< cb_t > > | callbacks |
Color | color |
std::list< Visualizer * > | cv_list |
bool | data_fresh |
bool | disabled |
unsigned int | event_queue_num |
std::list< Flag * > | flag_list |
double | friction |
Geom | geom |
class Stg::Model::GuiState | gui |
bool | has_default_block |
uint32_t | id |
usec_t | interval |
time between updates in usec | |
usec_t | interval_energy |
time between updates of powerpack in usec | |
usec_t | last_update |
time of last update in us | |
bool | log_state |
iff true, model state is logged | |
meters_t | map_resolution |
kg_t | mass |
Model * | parent |
Pose | pose |
PowerPack * | power_pack |
std::list< PowerPack * > | pps_charging |
Stg::Model::RasterVis | rastervis |
bool | rebuild_displaylist |
iff true, regenerate block display list before redraw | |
std::string | say_string |
if non-empty, this string is displayed in the GUI | |
bool | stack_children |
whether child models should be stacked on top of this model or not | |
bool | stall |
Set to true iff the model collided with something else. | |
int | subs |
the number of subscriptions to this model | |
bool | thread_safe |
std::vector< TrailItem > | trail |
unsigned int | trail_index |
const std::string | type |
bool | used |
TRUE iff this model has been returned by GetUnusedModelOfType() | |
watts_t | watts |
power consumed by this model | |
watts_t | watts_give |
watts_t | watts_take |
Worldfile * | wf |
int | wf_entity |
World * | world |
WorldGui * | world_gui |
Static Protected Attributes | |
static uint64_t | trail_interval |
static unsigned int | trail_length |
Private Member Functions | |
const std::vector< Option * > & | getOptions () const |
Model (const Model &original) | |
Model & | operator= (const Model &original) |
Private Attributes | |
std::vector< Option * > | drawOptions |
bool | mapped |
Static Private Attributes | |
static uint32_t | count |
static std::map< id_t, Model * > | modelsbyid |
Friends | |
class | Ancestor |
class | Block |
class | BlockGroup |
class | Canvas |
class | ModelFiducial |
class | PowerPack |
class | Ray |
class | Region |
class | World |
class | World::Event |
class | WorldGui |
Stg::Model::Model | ( | const Model & | original | ) | [explicit, private] |
Private copy constructor declared but not defined, to make it impossible to copy models.
Model::Model | ( | World * | world, |
Model * | parent = NULL , |
||
const std::string & | type = "model" , |
||
const std::string & | name = "" |
||
) |
Model::~Model | ( | void | ) | [virtual] |
Stg::Model::Model | ( | ) | [inline] |
void Model::AddCallback | ( | callback_type_t | type, |
model_callback_t | cb, | ||
void * | user | ||
) |
Add a callback. The specified function is called whenever the indicated model method is called, and passed the user data.
cb | Pointer the function to be called. |
user | Pointer to arbitrary user data, passed to the callback when called. |
Definition at line 6 of file model_callbacks.cc.
void Model::AddFlag | ( | Flag * | flag | ) |
void Model::AddToPose | ( | const Pose & | pose | ) |
void Model::AddToPose | ( | double | dx, |
double | dy, | ||
double | dz, | ||
double | da | ||
) |
void Model::AddVisualizer | ( | Visualizer * | custom_visual, |
bool | on_by_default | ||
) |
Attach a user supplied visualization to a model.
Definition at line 322 of file model_draw.cc.
void Model::AppendTouchingModels | ( | std::set< Model * > & | touchers | ) | [protected] |
void Model::BecomeParentOf | ( | Model * | child | ) |
int Model::CallCallbacks | ( | callback_type_t | type | ) |
Definition at line 41 of file model_callbacks.cc.
void Model::CallUpdateCallbacks | ( | void | ) | [protected] |
void Model::ClearBlocks | ( | ) |
void Stg::Model::CommitTestedPose | ( | ) | [protected] |
bool Stg::Model::DataIsFresh | ( | ) | const [inline] |
void Model::DataVisualize | ( | Camera * | cam | ) | [protected, virtual] |
Reimplemented in Stg::ModelCamera, Stg::ModelBlinkenlight, Stg::ModelFiducial, and Stg::ModelGripper.
Definition at line 627 of file model_draw.cc.
void Model::DataVisualizeTree | ( | Camera * | cam | ) | [protected] |
Definition at line 632 of file model_draw.cc.
void Stg::Model::Disable | ( | ) | [inline] |
void Model::DrawBlocks | ( | ) | [protected, virtual] |
Reimplemented in Stg::ModelLightIndicator.
Definition at line 251 of file model_draw.cc.
void Model::DrawBlocksTree | ( | ) | [protected] |
Definition at line 228 of file model_draw.cc.
void Model::DrawBoundingBox | ( | ) | [protected] |
Definition at line 267 of file model_draw.cc.
void Model::DrawBoundingBoxTree | ( | ) | [protected] |
Definition at line 256 of file model_draw.cc.
void Model::DrawFlagList | ( | void | ) | [protected] |
Definition at line 522 of file model_draw.cc.
void Model::DrawGrid | ( | void | ) | [protected] |
Definition at line 655 of file model_draw.cc.
void Model::DrawImage | ( | uint32_t | texture_id, |
Camera * | cam, | ||
float | alpha, | ||
double | width = 1.0 , |
||
double | height = 1.0 |
||
) | [protected] |
Draw the image stored in texture_id above the model
Definition at line 469 of file model_draw.cc.
void Stg::Model::DrawOrigin | ( | ) | [protected] |
void Model::DrawOriginTree | ( | ) | [protected] |
Definition at line 219 of file model_draw.cc.
void Model::DrawPicker | ( | void | ) | [protected, virtual] |
Definition at line 612 of file model_draw.cc.
void Model::DrawPose | ( | Pose | pose | ) | [protected] |
Definition at line 239 of file model_draw.cc.
void Model::DrawSelected | ( | void | ) | [protected, virtual] |
Definition at line 12 of file model_draw.cc.
void Model::DrawStatus | ( | Camera * | cam | ) | [protected, virtual] |
Definition at line 366 of file model_draw.cc.
void Model::DrawStatusTree | ( | Camera * | cam | ) | [protected] |
Definition at line 357 of file model_draw.cc.
void Model::DrawTrailArrows | ( | ) | [protected] |
Definition at line 184 of file model_draw.cc.
void Model::DrawTrailBlocks | ( | ) | [protected] |
Definition at line 163 of file model_draw.cc.
void Model::DrawTrailFootprint | ( | ) | [protected] |
Definition at line 126 of file model_draw.cc.
void Stg::Model::Enable | ( | ) | [inline] |
PowerPack * Model::FindPowerPack | ( | ) | const |
Model * Model::GetChild | ( | const std::string & | name | ) | const |
Color Stg::Model::GetColor | ( | ) | const [inline] |
usec_t Stg::Model::GetEnergyInterval | ( | ) | const [inline] |
int Stg::Model::GetFiducialReturn | ( | ) | const [inline] |
unsigned int Stg::Model::GetFlagCount | ( | ) | const [inline] |
Geom Stg::Model::GetGeom | ( | ) | const [inline] |
Pose Model::GetGlobalPose | ( | ) | const [virtual] |
get the pose of a model in the global CS
Reimplemented from Stg::Ancestor.
Velocity Stg::Model::GetGlobalVelocity | ( | ) | const |
get the velocity of a model in the global CS
uint32_t Stg::Model::GetId | ( | ) | const [inline] |
usec_t Stg::Model::GetInterval | ( | ) | [inline] |
kg_t Model::GetMassOfChildren | ( | ) | const |
const std::string& Stg::Model::GetModelType | ( | ) | const [inline] |
const std::vector<Option*>& Stg::Model::getOptions | ( | ) | const [inline, private] |
Pose Stg::Model::GetPose | ( | ) | const [inline] |
std::string Stg::Model::GetSayString | ( | ) | [inline] |
unsigned int Stg::Model::GetSubscriptionCount | ( | ) | const [inline] |
kg_t Model::GetTotalMass | ( | ) | const |
Model * Model::GetUnsubscribedModelOfType | ( | const std::string & | type | ) | const |
Model * Model::GetUnusedModelOfType | ( | const std::string & | type | ) |
usec_t Stg::Model::GetUpdateInterval | ( | ) | const [inline] |
World* Stg::Model::GetWorld | ( | ) | const [inline] |
Pose Model::GlobalToLocal | ( | const Pose & | pose | ) | const |
bool Stg::Model::HasSubscribers | ( | ) | const [inline] |
void Model::InitControllers | ( | ) |
bool Model::IsAntecedent | ( | const Model * | testmod | ) | const |
bool Model::IsDescendent | ( | const Model * | testmod | ) | const |
bool Model::IsRelated | ( | const Model * | testmod | ) | const |
void Stg::Model::Load | ( | Worldfile * | wf, |
int | wf_entity | ||
) | [inline] |
Set the worldfile and worldfile entity ID - must be called before Load()
Reimplemented from Stg::Ancestor.
void Model::Load | ( | void | ) | [virtual] |
configure a model by reading from the current world file
Reimplemented in Stg::ModelActuator, Stg::ModelPosition, Stg::ModelCamera, Stg::ModelBlinkenlight, Stg::ModelRanger, Stg::ModelFiducial, Stg::ModelGripper, and Stg::ModelBlobfinder.
void Model::LoadBlock | ( | Worldfile * | wf, |
int | entity | ||
) |
void Model::LoadControllerModule | ( | const char * | lib | ) |
Pose Stg::Model::LocalToGlobal | ( | const Pose & | pose | ) | const [inline] |
point_t Model::LocalToGlobal | ( | const point_t & | pt | ) | const |
std::vector< point_int_t > Model::LocalToPixels | ( | const std::vector< point_t > & | local | ) | const |
static Model* Stg::Model::LookupId | ( | uint32_t | id | ) | [inline, static] |
void Model::Map | ( | unsigned int | layer | ) | [protected] |
void Stg::Model::Map | ( | ) | [inline, protected] |
void Model::MapFromRoot | ( | unsigned int | layer | ) | [protected] |
void Model::MapWithChildren | ( | unsigned int | layer | ) | [protected] |
meters_t Model::ModelHeight | ( | ) | const [protected] |
void Model::NeedRedraw | ( | void | ) |
Private assignment operator declared but not defined, to make it impossible to copy models
Model* Stg::Model::Parent | ( | ) | const [inline] |
void Model::PlaceInFreeSpace | ( | meters_t | xmin, |
meters_t | xmax, | ||
meters_t | ymin, | ||
meters_t | ymax | ||
) |
virtual void Stg::Model::PopColor | ( | ) | [inline, virtual] |
void Model::PopCoords | ( | ) | [protected] |
Definition at line 317 of file model_draw.cc.
Model::Flag * Model::PopFlag | ( | ) |
std::string Stg::Model::PoseString | ( | ) | [inline] |
void Model::Print | ( | char * | prefix | ) | const [virtual] |
Reimplemented in Stg::ModelRanger.
const char * Model::PrintWithPose | ( | ) | const [virtual] |
virtual void Stg::Model::PushColor | ( | Color | col | ) | [inline, virtual] |
virtual void Stg::Model::PushColor | ( | double | r, |
double | g, | ||
double | b, | ||
double | a | ||
) | [inline, virtual] |
void Model::PushFlag | ( | Flag * | flag | ) |
void Model::PushLocalCoords | ( | ) | [protected] |
Definition at line 307 of file model_draw.cc.
void Model::Rasterize | ( | uint8_t * | data, |
unsigned int | width, | ||
unsigned int | height, | ||
meters_t | cellwidth, | ||
meters_t | cellheight | ||
) |
RaytraceResult Model::Raytrace | ( | const Pose & | pose, |
const meters_t | range, | ||
const ray_test_func_t | func, | ||
const void * | arg, | ||
const bool | ztest = true |
||
) | [protected] |
void Stg::Model::Raytrace | ( | const Pose & | pose, |
const meters_t | range, | ||
const radians_t | fov, | ||
const ray_test_func_t | func, | ||
const void * | arg, | ||
RaytraceResult * | samples, | ||
const uint32_t | sample_count, | ||
const bool | ztest = true |
||
) | [protected] |
raytraces multiple rays around the point and heading identified by pose, in local coords
RaytraceResult Model::Raytrace | ( | const radians_t | bearing, |
const meters_t | range, | ||
const ray_test_func_t | func, | ||
const void * | arg, | ||
const bool | ztest = true |
||
) | [protected] |
void Model::Raytrace | ( | const radians_t | bearing, |
const meters_t | range, | ||
const radians_t | fov, | ||
const ray_test_func_t | func, | ||
const void * | arg, | ||
RaytraceResult * | samples, | ||
const uint32_t | sample_count, | ||
const bool | ztest = true |
||
) | [protected] |
void Model::Redraw | ( | void | ) |
void Model::RegisterOption | ( | Option * | opt | ) | [protected] |
int Model::RemoveCallback | ( | callback_type_t | type, |
model_callback_t | callback | ||
) |
Definition at line 22 of file model_callbacks.cc.
void Model::RemoveFlag | ( | Flag * | flag | ) |
void Model::RemoveVisualizer | ( | Visualizer * | custom_visual | ) |
remove user supplied visualization to a model - supply the same ptr passed to AddCustomVisualizer
Definition at line 348 of file model_draw.cc.
Model* Stg::Model::Root | ( | ) | [inline] |
void Model::Save | ( | void | ) | [virtual] |
save the state of the model to the current world file
Reimplemented in Stg::ModelGripper.
void Model::Say | ( | const std::string & | str | ) |
void Model::SetBlobReturn | ( | bool | val | ) |
void Model::SetBoundary | ( | bool | val | ) |
void Model::SetColor | ( | Color | col | ) |
void Model::SetFiducialKey | ( | int | key | ) |
void Model::SetFiducialReturn | ( | int | fid | ) |
void Model::SetFriction | ( | double | friction | ) |
void Model::SetGeom | ( | const Geom & | src | ) |
void Model::SetGlobalPose | ( | const Pose & | gpose | ) |
void Stg::Model::SetGlobalVelocity | ( | const Velocity & | gvel | ) |
void Stg::Model::SetGravityReturn | ( | bool | val | ) |
void Model::SetGripperReturn | ( | bool | val | ) |
void Model::SetGuiGrid | ( | bool | val | ) |
void Model::SetGuiMove | ( | bool | val | ) |
void Model::SetGuiNose | ( | bool | val | ) |
void Model::SetGuiOutline | ( | bool | val | ) |
void Model::SetMapResolution | ( | meters_t | res | ) |
void Model::SetMass | ( | kg_t | mass | ) |
void Model::SetObstacleReturn | ( | bool | val | ) |
int Model::SetParent | ( | Model * | newparent | ) |
void Model::SetPose | ( | const Pose & | pose | ) |
void Model::SetRangerReturn | ( | double | val | ) |
void Stg::Model::SetRangerReturn | ( | bool | val | ) |
void Model::SetStall | ( | bool | stall | ) |
void Stg::Model::SetStickyReturn | ( | bool | val | ) |
virtual void Stg::Model::SetToken | ( | const std::string & | str | ) | [inline, virtual] |
Reimplemented from Stg::Ancestor.
void Model::SetWatts | ( | watts_t | watts | ) |
void Stg::Model::SetWorldfile | ( | Worldfile * | wf, |
int | wf_entity | ||
) | [inline] |
void Model::Shutdown | ( | void | ) | [protected, virtual] |
Reimplemented in Stg::ModelActuator, Stg::ModelPosition, Stg::ModelRanger, Stg::ModelFiducial, and Stg::ModelBlobfinder.
bool Stg::Model::Stalled | ( | ) | const [inline] |
void Model::Startup | ( | void | ) | [protected, virtual] |
Reimplemented in Stg::ModelActuator, Stg::ModelPosition, Stg::ModelRanger, and Stg::ModelBlobfinder.
void Model::Subscribe | ( | void | ) |
Model * Model::TestCollision | ( | ) | [protected] |
Check to see if the current pose will yield a collision with obstacles. Returns a pointer to the first entity we are in collision with, or NULL if no collision exists. Recursively calls TestCollision() on all descendents.
void Model::UnMap | ( | unsigned int | layer | ) | [protected] |
void Stg::Model::UnMap | ( | ) | [inline, protected] |
void Model::UnMapFromRoot | ( | unsigned int | layer | ) | [protected] |
void Model::UnMapWithChildren | ( | unsigned int | layer | ) | [protected] |
void Model::Unsubscribe | ( | void | ) |
void Model::Update | ( | void | ) | [protected, virtual] |
void Model::UpdateCharge | ( | ) | [protected, virtual] |
void Model::UpdateTrail | ( | ) | [protected] |
static int Stg::Model::UpdateWrapper | ( | Model * | mod, |
void * | arg | ||
) | [inline, static, protected] |
friend class BlockGroup [friend] |
friend class Canvas [friend] |
Reimplemented from Stg::Ancestor.
Reimplemented in Stg::ModelPosition.
friend class ModelFiducial [friend] |
friend class World::Event [friend] |
bool Stg::Model::alwayson [protected] |
BlockGroup Stg::Model::blockgroup [protected] |
int Stg::Model::blocks_dl [protected] |
int Stg::Model::boundary [protected] |
std::vector<std::set<cb_t> > Stg::Model::callbacks [protected] |
Color Stg::Model::color [protected] |
uint32_t Model::count [static, private] |
std::list<Visualizer*> Stg::Model::cv_list [protected] |
bool Stg::Model::data_fresh [protected] |
bool Stg::Model::disabled [protected] |
std::vector<Option*> Stg::Model::drawOptions [private] |
unsigned int Stg::Model::event_queue_num [protected] |
std::list<Flag*> Stg::Model::flag_list [protected] |
double Stg::Model::friction [protected] |
Geom Stg::Model::geom [protected] |
class Stg::Model::GuiState Stg::Model::gui [protected] |
bool Stg::Model::has_default_block [protected] |
uint32_t Stg::Model::id [protected] |
usec_t Stg::Model::interval [protected] |
usec_t Stg::Model::interval_energy [protected] |
usec_t Stg::Model::last_update [protected] |
bool Stg::Model::log_state [protected] |
meters_t Stg::Model::map_resolution [protected] |
bool Stg::Model::mapped [private] |
kg_t Stg::Model::mass [protected] |
std::map< Stg::id_t, Model * > Model::modelsbyid [static, private] |
std::map< std::string, creator_t > Model::name_map [static] |
Model* Stg::Model::parent [protected] |
Pose Stg::Model::pose [protected] |
PowerPack* Stg::Model::power_pack [protected] |
std::list<PowerPack*> Stg::Model::pps_charging [protected] |
Stg::Model::RasterVis Stg::Model::rastervis [protected] |
bool Stg::Model::rebuild_displaylist [protected] |
std::string Stg::Model::say_string [protected] |
bool Stg::Model::stack_children [protected] |
bool Stg::Model::stall [protected] |
int Stg::Model::subs [protected] |
bool Stg::Model::thread_safe [protected] |
std::vector<TrailItem> Stg::Model::trail [protected] |
unsigned int Stg::Model::trail_index [protected] |
uint64_t Model::trail_interval [static, protected] |
uint32_t Model::trail_length [static, protected] |
const std::string Stg::Model::type [protected] |
bool Stg::Model::used [protected] |
TRUE iff this model has been returned by GetUnusedModelOfType()
Reimplemented in Stg::ModelRanger, and Stg::ModelBlobfinder.
watts_t Stg::Model::watts [protected] |
watts_t Stg::Model::watts_give [protected] |
watts_t Stg::Model::watts_take [protected] |
Worldfile* Stg::Model::wf [protected] |
int Stg::Model::wf_entity [protected] |
World* Stg::Model::world [protected] |
WorldGui* Stg::Model::world_gui [protected] |