Classes | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Static Protected Attributes | Private Member Functions | Private Attributes | Static Private Attributes | Friends
Stg::Model Class Reference

Model class More...

#include <stage.hh>

Inheritance diagram for Stg::Model:
Inheritance graph
[legend]

List of all members.

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

BlockAddBlockRect (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 ()
PowerPackFindPowerPack () const
ModelGetChild (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
ModelGetUnsubscribedModelOfType (const std::string &type) const
ModelGetUnusedModelOfType (const std::string &type)
usec_t GetUpdateInterval () const
WorldGetWorld () 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_tLocalToPixels (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 ()
ModelParent () const
void PlaceInFreeSpace (meters_t xmin, meters_t xmax, meters_t ymin, meters_t ymax)
virtual void PopColor ()
FlagPopFlag ()
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)
ModelRoot ()
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 ModelLookupId (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 ()
ModelTestCollision ()
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
Modelparent
Pose pose
PowerPackpower_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< TrailItemtrail
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
Worldfilewf
int wf_entity
Worldworld
WorldGuiworld_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)
Modeloperator= (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

Detailed Description

Model class

Definition at line 1742 of file stage.hh.


Member Enumeration Documentation

Enumerator:
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 

Definition at line 1835 of file stage.hh.


Constructor & Destructor Documentation

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 = "" 
)

Constructor

Definition at line 243 of file model.cc.

Model::~Model ( void  ) [virtual]

Destructor

Definition at line 356 of file model.cc.

Stg::Model::Model ( ) [inline]

Alternate constructor that creates dummy models with only a pose

Definition at line 2219 of file stage.hh.


Member Function Documentation

Block * Model::AddBlockRect ( meters_t  x,
meters_t  y,
meters_t  dx,
meters_t  dy,
meters_t  dz 
)

Add a block to this model centered at [x,y] with extent [dx, dy, dz]

Definition at line 442 of file model.cc.

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.

Parameters:
cbPointer the function to be called.
userPointer to arbitrary user data, passed to the callback when called.

Definition at line 6 of file model_callbacks.cc.

void Model::AddFlag ( Flag flag)

Definition at line 381 of file model.cc.

void Model::AddToPose ( const Pose pose)

add values to a model's pose in its parent's coordinate system

Definition at line 782 of file model.cc.

void Model::AddToPose ( double  dx,
double  dy,
double  dz,
double  da 
)

add values to a model's pose in its parent's coordinate system

Definition at line 771 of file model.cc.

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]

Definition at line 794 of file model.cc.

void Model::BecomeParentOf ( Model child)

Definition at line 971 of file model.cc.

Definition at line 41 of file model_callbacks.cc.

void Model::CallUpdateCallbacks ( void  ) [protected]

Calls CallCallback( CB_UPDATE )

Definition at line 756 of file model.cc.

remove all blocks from this model, freeing their memory

Definition at line 421 of file model.cc.

void Stg::Model::CommitTestedPose ( ) [protected]
bool Stg::Model::DataIsFresh ( ) const [inline]

Definition at line 2405 of file stage.hh.

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]

Disable the model. Its pose will not change due to velocity until re-enabled using Enable(). This is used for example when dragging a model with the mouse pointer. The model is enabled by default.

Definition at line 2267 of file stage.hh.

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]

Enable the model, so that non-zero velocities will change the model's pose. Models are enabled by default.

Definition at line 2271 of file stage.hh.

Definition at line 985 of file model.cc.

Model * Model::GetChild ( const std::string &  name) const

Returns a pointer to the model identified by name, or NULL if it doesn't exist in this model.

Definition at line 1018 of file model.cc.

Color Stg::Model::GetColor ( ) const [inline]

Definition at line 2362 of file stage.hh.

Definition at line 2063 of file stage.hh.

int Stg::Model::GetFiducialReturn ( ) const [inline]

Get a model's fiducial return value.

Definition at line 2356 of file stage.hh.

unsigned int Stg::Model::GetFlagCount ( ) const [inline]

Definition at line 2261 of file stage.hh.

Geom Stg::Model::GetGeom ( ) const [inline]

Get (a copy of) the model's geometry - it's size and local pose (offset from origin in local coords).

Definition at line 2378 of file stage.hh.

Pose Model::GetGlobalPose ( ) const [virtual]

get the pose of a model in the global CS

Reimplemented from Stg::Ancestor.

Definition at line 1379 of file model.cc.

get the velocity of a model in the global CS

uint32_t Stg::Model::GetId ( ) const [inline]

return a model's unique process-wide identifier

Definition at line 2365 of file stage.hh.

return the update interval in usec

Definition at line 2044 of file stage.hh.

Get the mass of this model's children recursively.

Definition at line 947 of file model.cc.

const std::string& Stg::Model::GetModelType ( ) const [inline]

Definition at line 2036 of file stage.hh.

const std::vector<Option*>& Stg::Model::getOptions ( ) const [inline, private]

Definition at line 1765 of file stage.hh.

Pose Stg::Model::GetPose ( ) const [inline]

Get (a copy of) the pose of a model in its parent's coordinate system.

Definition at line 2382 of file stage.hh.

std::string Stg::Model::GetSayString ( ) [inline]

Definition at line 2037 of file stage.hh.

unsigned int Stg::Model::GetSubscriptionCount ( ) const [inline]

Returns the current number of subscriptions. If alwayson, this is never less than 1.

Definition at line 2461 of file stage.hh.

Get the total mass of a model and it's children recursively

Definition at line 937 of file model.cc.

Model * Model::GetUnsubscribedModelOfType ( const std::string &  type) const

returns the first descendent of this model that is unsubscribed and has the type indicated by the string

Definition at line 882 of file model.cc.

Model * Model::GetUnusedModelOfType ( const std::string &  type)

returns the first descendent of this model that is unused and has the type indicated by the string. This model is tagged as used.

Definition at line 914 of file model.cc.

Definition at line 2062 of file stage.hh.

World* Stg::Model::GetWorld ( ) const [inline]

Returns a pointer to the world that contains this model

Definition at line 2302 of file stage.hh.

Pose Model::GlobalToLocal ( const Pose pose) const

Given a global pose, returns that pose in the model's local coordinate system.

Definition at line 525 of file model.cc.

bool Stg::Model::HasSubscribers ( ) const [inline]

Returns true if the model has one or more subscribers, else false.

Definition at line 2464 of file stage.hh.

Call Init() for all attached controllers.

Definition at line 375 of file model.cc.

bool Model::IsAntecedent ( const Model testmod) const

Definition at line 545 of file model.cc.

bool Model::IsDescendent ( const Model testmod) const

returns true if model [testmod] is a descendent of this model

Definition at line 557 of file model.cc.

bool Model::IsRelated ( const Model testmod) const

returns true if model [testmod] is a descendent or antecedent of this model

Definition at line 570 of file model.cc.

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.

Definition at line 2234 of file stage.hh.

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.

Definition at line 1422 of file model.cc.

void Model::LoadBlock ( Worldfile wf,
int  entity 
)

Add a block to this model by loading it from a worldfile entity

Definition at line 430 of file model.cc.

void Model::LoadControllerModule ( const char *  lib)

Load a control program for this model from an external library

Definition at line 1672 of file model.cc.

Pose Stg::Model::LocalToGlobal ( const Pose pose) const [inline]

Return the global pose (i.e. pose in world coordinates) of a pose specified in the model's local coordinate system

Definition at line 2435 of file stage.hh.

point_t Model::LocalToGlobal ( const point_t pt) const

Return the 2d point in world coordinates of a 2d point specified in the model's local coordinate system

Definition at line 593 of file model.cc.

std::vector< point_int_t > Model::LocalToPixels ( const std::vector< point_t > &  local) const

Return a vector of global pixels corresponding to a vector of local points.

Definition at line 600 of file model.cc.

static Model* Stg::Model::LookupId ( uint32_t  id) [inline, static]

Look up a model pointer by a unique model ID

Definition at line 2206 of file stage.hh.

void Model::Map ( unsigned int  layer) [protected]

Definition at line 952 of file model.cc.

void Stg::Model::Map ( ) [inline, protected]

Call Map on all layers

Definition at line 2099 of file stage.hh.

void Model::MapFromRoot ( unsigned int  layer) [protected]

Definition at line 627 of file model.cc.

void Model::MapWithChildren ( unsigned int  layer) [protected]

Definition at line 617 of file model.cc.

meters_t Model::ModelHeight ( ) const [protected]

Definition at line 761 of file model.cc.

void Model::NeedRedraw ( void  )

Sets the redraw flag, so this model will be redrawn at the earliest opportunity

Definition at line 899 of file model.cc.

Model& Stg::Model::operator= ( const Model original) [private]

Private assignment operator declared but not defined, to make it impossible to copy models

Model* Stg::Model::Parent ( ) const [inline]

Returns a pointer to this model's parent model, or NULL if this model has no parent

Definition at line 2299 of file stage.hh.

void Model::PlaceInFreeSpace ( meters_t  xmin,
meters_t  xmax,
meters_t  ymin,
meters_t  ymax 
)

Definition at line 787 of file model.cc.

virtual void Stg::Model::PopColor ( ) [inline, virtual]

Definition at line 2191 of file stage.hh.

void Model::PopCoords ( ) [protected]

Definition at line 317 of file model_draw.cc.

Definition at line 408 of file model.cc.

std::string Stg::Model::PoseString ( ) [inline]

Return a human-readable string describing the model's pose

Definition at line 2202 of file stage.hh.

void Model::Print ( char *  prefix) const [virtual]

Reimplemented in Stg::ModelRanger.

Definition at line 680 of file model.cc.

const char * Model::PrintWithPose ( ) const [virtual]

Definition at line 695 of file model.cc.

virtual void Stg::Model::PushColor ( Color  col) [inline, virtual]

Definition at line 2189 of file stage.hh.

virtual void Stg::Model::PushColor ( double  r,
double  g,
double  b,
double  a 
) [inline, virtual]

Definition at line 2190 of file stage.hh.

void Model::PushFlag ( Flag flag)

Definition at line 399 of file model.cc.

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 
)

Render the model's blocks as an occupancy grid into the preallocated array of width by height pixels

Definition at line 1002 of file model.cc.

RaytraceResult Model::Raytrace ( const Pose pose,
const meters_t  range,
const ray_test_func_t  func,
const void *  arg,
const bool  ztest = true 
) [protected]

raytraces a single ray from the point and heading identified by pose, in local coords

Definition at line 475 of file model.cc.

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]

Definition at line 489 of file model.cc.

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]

Definition at line 504 of file model.cc.

void Model::Redraw ( void  )

Force the GUI (if any) to redraw this model

Definition at line 909 of file model.cc.

void Model::RegisterOption ( Option opt) [protected]

Register an Option for pickup by the GUI.

Definition at line 996 of file model.cc.

Definition at line 22 of file model_callbacks.cc.

void Model::RemoveFlag ( Flag flag)

Definition at line 390 of file model.cc.

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]

return the root model of the tree containing this model

Definition at line 2305 of file stage.hh.

void Model::Save ( void  ) [virtual]

save the state of the model to the current world file

Reimplemented in Stg::ModelGripper.

Definition at line 1633 of file model.cc.

void Model::Say ( const std::string &  str)

Definition at line 539 of file model.cc.

void Model::SetBlobReturn ( bool  val)

Definition at line 1303 of file model.cc.

void Model::SetBoundary ( bool  val)

Definition at line 1313 of file model.cc.

void Model::SetColor ( Color  col)

Definition at line 1260 of file model.cc.

void Model::SetFiducialKey ( int  key)

set a model's fiducial key: only fiducial finders with a matching key can detect this model as a fiducial.

Definition at line 1293 of file model.cc.

void Model::SetFiducialReturn ( int  fid)

Set a model's fiducial return value. Values less than zero are not detected by the fiducial sensor.

Definition at line 1281 of file model.cc.

void Model::SetFriction ( double  friction)

Definition at line 1013 of file model.cc.

void Model::SetGeom ( const Geom src)

set a model's geometry (size and center offsets)

Definition at line 1243 of file model.cc.

void Model::SetGlobalPose ( const Pose gpose)

set the pose of model in global coordinates

Definition at line 1349 of file model.cc.

void Stg::Model::SetGlobalVelocity ( const Velocity gvel)
void Stg::Model::SetGravityReturn ( bool  val)
void Model::SetGripperReturn ( bool  val)

Definition at line 1276 of file model.cc.

void Model::SetGuiGrid ( bool  val)

Definition at line 1328 of file model.cc.

void Model::SetGuiMove ( bool  val)

Definition at line 1323 of file model.cc.

void Model::SetGuiNose ( bool  val)

Definition at line 1318 of file model.cc.

void Model::SetGuiOutline ( bool  val)

Definition at line 1333 of file model.cc.

Definition at line 1343 of file model.cc.

void Model::SetMass ( kg_t  mass)

Definition at line 1266 of file model.cc.

void Model::SetObstacleReturn ( bool  val)

Definition at line 1298 of file model.cc.

int Model::SetParent ( Model newparent)

Change a model's parent - experimental

Definition at line 1354 of file model.cc.

void Model::SetPose ( const Pose pose)

Enable update of model pose according to velocity state Disable update of model pose according to velocity state set a model's pose in its parent's coordinate system

Definition at line 1396 of file model.cc.

void Model::SetRangerReturn ( double  val)

Definition at line 1308 of file model.cc.

void Stg::Model::SetRangerReturn ( bool  val)
void Model::SetStall ( bool  stall)

Definition at line 1271 of file model.cc.

void Stg::Model::SetStickyReturn ( bool  val)
virtual void Stg::Model::SetToken ( const std::string &  str) [inline, virtual]

Reimplemented from Stg::Ancestor.

Definition at line 2022 of file stage.hh.

void Model::SetWatts ( watts_t  watts)

Definition at line 1338 of file model.cc.

void Stg::Model::SetWorldfile ( Worldfile wf,
int  wf_entity 
) [inline]

Set the worldfile and worldfile entity ID

Definition at line 2243 of file stage.hh.

void Model::Shutdown ( void  ) [protected, virtual]
bool Stg::Model::Stalled ( ) const [inline]

Returns the value of the model's stall boolean, which is true iff the model has crashed into another model

Definition at line 2457 of file stage.hh.

void Model::Startup ( void  ) [protected, virtual]

Reimplemented in Stg::ModelActuator, Stg::ModelPosition, Stg::ModelRanger, and Stg::ModelBlobfinder.

Definition at line 707 of file model.cc.

void Model::Subscribe ( void  )

subscribe to a model's data

Definition at line 646 of file model.cc.

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.

Definition at line 800 of file model.cc.

void Model::UnMap ( unsigned int  layer) [protected]

Definition at line 962 of file model.cc.

void Stg::Model::UnMap ( ) [inline, protected]

Call UnMap on all layers

Definition at line 2104 of file stage.hh.

void Model::UnMapFromRoot ( unsigned int  layer) [protected]

Definition at line 641 of file model.cc.

void Model::UnMapWithChildren ( unsigned int  layer) [protected]

Definition at line 632 of file model.cc.

void Model::Unsubscribe ( void  )

unsubscribe from a model's data

Definition at line 659 of file model.cc.

void Model::Update ( void  ) [protected, virtual]
void Model::UpdateCharge ( ) [protected, virtual]

Definition at line 816 of file model.cc.

void Model::UpdateTrail ( ) [protected]

Record the current pose in our trail. Delete the trail head if it is full.

Definition at line 868 of file model.cc.

static int Stg::Model::UpdateWrapper ( Model mod,
void *  arg 
) [inline, static, protected]

Definition at line 2152 of file stage.hh.


Friends And Related Function Documentation

friend class Ancestor [friend]

Definition at line 1744 of file stage.hh.

friend class Block [friend]

Definition at line 1749 of file stage.hh.

friend class BlockGroup [friend]

Definition at line 1751 of file stage.hh.

friend class Canvas [friend]

Reimplemented from Stg::Ancestor.

Reimplemented in Stg::ModelPosition.

Definition at line 1748 of file stage.hh.

friend class ModelFiducial [friend]

Definition at line 1754 of file stage.hh.

friend class PowerPack [friend]

Definition at line 1752 of file stage.hh.

friend class Ray [friend]

Definition at line 1753 of file stage.hh.

friend class Region [friend]

Definition at line 1750 of file stage.hh.

friend class World [friend]

Definition at line 1745 of file stage.hh.

friend class World::Event [friend]

Definition at line 1746 of file stage.hh.

friend class WorldGui [friend]

Definition at line 1747 of file stage.hh.


Member Data Documentation

bool Stg::Model::alwayson [protected]

If true, the model always has at least one subscription, so always runs. Defaults to false.

Definition at line 1771 of file stage.hh.

Definition at line 1773 of file stage.hh.

int Stg::Model::blocks_dl [protected]

OpenGL display list identifier for the blockgroup

Definition at line 1775 of file stage.hh.

int Stg::Model::boundary [protected]

Iff true, 4 thin blocks are automatically added to the model, forming a solid boundary around the bounding box of the model.

Definition at line 1780 of file stage.hh.

std::vector<std::set<cb_t> > Stg::Model::callbacks [protected]

A list of callback functions can be attached to any address. When Model::CallCallbacks( void*) is called, the callbacks are called.

Definition at line 1856 of file stage.hh.

Color Stg::Model::color [protected]

Default color of the model's blocks.

Definition at line 1859 of file stage.hh.

uint32_t Model::count [static, private]

the number of models instatiated - used to assign unique IDs

Definition at line 1758 of file stage.hh.

std::list<Visualizer*> Stg::Model::cv_list [protected]

Container for Visualizers attached to this model.

Definition at line 1872 of file stage.hh.

bool Stg::Model::data_fresh [protected]

This can be set to indicate that the model has new data that may be of interest to users. This allows polling the model instead of adding a data callback.

Definition at line 1864 of file stage.hh.

bool Stg::Model::disabled [protected]

If set true, Update() is not called on this model. Useful e.g. for temporarily disabling updates when dragging models with the mouse.

Definition at line 1869 of file stage.hh.

std::vector<Option*> Stg::Model::drawOptions [private]

Definition at line 1764 of file stage.hh.

unsigned int Stg::Model::event_queue_num [protected]

The index into the world's vector of event queues. Initially -1, to indicate that it is not on a list yet.

Definition at line 2002 of file stage.hh.

std::list<Flag*> Stg::Model::flag_list [protected]

Container for flags attached to this model.

Definition at line 1875 of file stage.hh.

double Stg::Model::friction [protected]

Model the interaction between the model's blocks and the surface they touch.

Todo:
primitive at the moment

Definition at line 1879 of file stage.hh.

Geom Stg::Model::geom [protected]

Specifies the the size of this model's bounding box, and the offset of its local coordinate system wrt that its parent.

Definition at line 1883 of file stage.hh.

Definition at line 1898 of file stage.hh.

uint32_t Stg::Model::id [protected]

unique process-wide identifier for this model

Definition at line 1901 of file stage.hh.

time between updates in usec

Definition at line 1902 of file stage.hh.

time between updates of powerpack in usec

Definition at line 1903 of file stage.hh.

time of last update in us

Definition at line 1906 of file stage.hh.

bool Stg::Model::log_state [protected]

iff true, model state is logged

Definition at line 1907 of file stage.hh.

Definition at line 1908 of file stage.hh.

bool Stg::Model::mapped [private]

records if this model has been mapped into the world bitmap

Definition at line 1762 of file stage.hh.

kg_t Stg::Model::mass [protected]

Definition at line 1909 of file stage.hh.

std::map< Stg::id_t, Model * > Model::modelsbyid [static, private]

Definition at line 1759 of file stage.hh.

std::map< std::string, creator_t > Model::name_map [static]

Definition at line 2466 of file stage.hh.

Model* Stg::Model::parent [protected]

Pointer to the parent of this model, possibly NULL.

Definition at line 1912 of file stage.hh.

Pose Stg::Model::pose [protected]

The pose of the model in it's parents coordinate frame, or the global coordinate frame is the parent is NULL.

Definition at line 1916 of file stage.hh.

Optional attached PowerPack, defaults to NULL

Definition at line 1919 of file stage.hh.

std::list<PowerPack*> Stg::Model::pps_charging [protected]

list of powerpacks that this model is currently charging, initially NULL.

Definition at line 1923 of file stage.hh.

iff true, regenerate block display list before redraw

Definition at line 1953 of file stage.hh.

std::string Stg::Model::say_string [protected]

if non-empty, this string is displayed in the GUI

Definition at line 1954 of file stage.hh.

bool Stg::Model::stack_children [protected]

whether child models should be stacked on top of this model or not

Definition at line 1956 of file stage.hh.

bool Stg::Model::stall [protected]

Set to true iff the model collided with something else.

Definition at line 1958 of file stage.hh.

int Stg::Model::subs [protected]

the number of subscriptions to this model

Definition at line 1959 of file stage.hh.

bool Stg::Model::thread_safe [protected]

Thread safety flag. Iff true, Update() may be called in parallel with other models. Defaults to false for safety. Derived classes can set it true in their constructor to allow parallel Updates().

Definition at line 1964 of file stage.hh.

std::vector<TrailItem> Stg::Model::trail [protected]

a ring buffer for storing recent poses

Definition at line 1982 of file stage.hh.

unsigned int Stg::Model::trail_index [protected]

current position in the ring buffer

Definition at line 1985 of file stage.hh.

uint64_t Model::trail_interval [static, protected]

Number of world updates between trail records.

Definition at line 1993 of file stage.hh.

uint32_t Model::trail_length [static, protected]

The maxiumum length of the trail drawn. Default is 20, but can be set in the world file using the tail_length model property.

Definition at line 1990 of file stage.hh.

const std::string Stg::Model::type [protected]

Definition at line 1999 of file stage.hh.

bool Stg::Model::used [protected]

TRUE iff this model has been returned by GetUnusedModelOfType()

Definition at line 2003 of file stage.hh.

Reimplemented in Stg::ModelRanger, and Stg::ModelBlobfinder.

power consumed by this model

Definition at line 2005 of file stage.hh.

If >0, this model can transfer energy to models that have watts_take >0

Definition at line 2009 of file stage.hh.

If >0, this model can transfer energy from models that have watts_give >0

Definition at line 2013 of file stage.hh.

Worldfile* Stg::Model::wf [protected]

Definition at line 2015 of file stage.hh.

int Stg::Model::wf_entity [protected]

Definition at line 2016 of file stage.hh.

World* Stg::Model::world [protected]

Definition at line 2017 of file stage.hh.

Definition at line 2018 of file stage.hh.


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


stage
Author(s): Richard Vaughan , Brian Gerkey , Reed Hedges , Andrew Howard , Toby Collett , Pooya Karimian , Jeremy Asher , Alex Couture-Beil , Geoff Biggs , Rich Mattes , Abbas Sadat
autogenerated on Thu Aug 27 2015 15:20:57