Stg::Model Class Reference

Model class More...

#include <stage.hh>

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

List of all members.

Classes

class  CallbackHooks
class  Flag
class  GuiState
class  RasterVis
class  stg_cb_t
class  TrailItem
class  Visibility

Public Member Functions

BlockAddBlockRect (stg_meters_t x, stg_meters_t y, stg_meters_t dx, stg_meters_t dy, stg_meters_t dz)
void AddCallback (void *address, stg_model_callback_t cb, void *user)
void AddFlag (Flag *flag)
void AddFlagDecrCallback (stg_model_callback_t cb, void *user)
void AddFlagIncrCallback (stg_model_callback_t cb, void *user)
void AddLoadCallback (stg_model_callback_t cb, void *user)
void AddSaveCallback (stg_model_callback_t cb, void *user)
void AddShutdownCallback (stg_model_callback_t cb, void *user)
void AddStartupCallback (stg_model_callback_t cb, void *user)
void AddToPose (double dx, double dy, double dz, double da)
void AddToPose (const Pose &pose)
void AddUpdateCallback (stg_model_callback_t cb, void *user)
void AddVisualizer (Visualizer *custom_visual, bool on_by_default)
void BecomeParentOf (Model *child)
int CallCallbacks (void *address)
void ClearBlocks ()
bool DataIsFresh () const
void Disable ()
void Enable ()
PowerPackFindPowerPack () const
ModelGetChild (const std::string &name) const
Color GetColor () const
stg_usec_t GetEnergyInterval ()
int GetFiducialReturn () const
int GetFlagCount () const
Geom GetGeom () const
Pose GetGlobalPose () const
Velocity GetGlobalVelocity () const
uint32_t GetId () const
stg_kg_t GetMassOfChildren ()
const std::string & GetModelType () const
Pose GetPose () const
stg_usec_t GetPoseInterval ()
std::string GetSayString ()
unsigned int GetSubscriptionCount () const
stg_kg_t GetTotalMass ()
ModelGetUnsubscribedModelOfType (const std::string &type) const
ModelGetUnusedModelOfType (const std::string &type)
stg_usec_t GetUpdateInterval ()
Velocity GetVelocity () 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
virtual void Load ()
void Load (Worldfile *wf, int wf_entity)
void LoadBlock (Worldfile *wf, int entity)
void LoadControllerModule (const char *lib)
stg_point_t LocalToGlobal (const stg_point_t &pt) const
Pose LocalToGlobal (const Pose &pose) const
void LocalToPixels (const std::vector< stg_point_t > &local, std::vector< stg_point_int_t > &pixels) const
 Model (World *world, Model *parent=NULL, const std::string &type="model")
void NeedRedraw ()
ModelParent () const
void PlaceInFreeSpace (stg_meters_t xmin, stg_meters_t xmax, stg_meters_t ymin, stg_meters_t ymax)
virtual void PopColor ()
FlagPopFlag ()
std::string PoseString ()
virtual void Print (char *prefix) const
virtual const char * PrintWithPose () const
virtual void PushColor (double r, double g, double b, double a)
virtual void PushColor (Color col)
void PushFlag (Flag *flag)
void Rasterize (uint8_t *data, unsigned int width, unsigned int height, stg_meters_t cellwidth, stg_meters_t cellheight)
int RemoveCallback (void *member, stg_model_callback_t callback)
void RemoveFlag (Flag *flag)
void RemoveFlagDecrCallback (stg_model_callback_t cb)
void RemoveFlagIncrCallback (stg_model_callback_t cb)
void RemoveLoadCallback (stg_model_callback_t cb)
void RemoveSaveCallback (stg_model_callback_t cb)
void RemoveShutdownCallback (stg_model_callback_t cb)
void RemoveStartupCallback (stg_model_callback_t cb)
void RemoveUpdateCallback (stg_model_callback_t cb)
void RemoveVisualizer (Visualizer *custom_visual)
ModelRoot ()
virtual void Save ()
void Say (const std::string &str)
void SetBlobReturn (int val)
void SetBoundary (int 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 (int val)
void SetGripperReturn (int val)
void SetGuiGrid (int val)
void SetGuiMove (int val)
void SetGuiNose (int val)
void SetGuiOutline (int val)
void SetLaserReturn (stg_laser_return_t val)
void SetMapResolution (stg_meters_t res)
void SetMass (stg_kg_t mass)
void SetObstacleReturn (int val)
int SetParent (Model *newparent)
void SetPose (const Pose &pose)
void SetRangerReturn (int val)
void SetStall (stg_bool_t stall)
void SetStickyReturn (int val)
void SetVelocity (const Velocity &vel)
void SetWatts (stg_watts_t watts)
void SetWorldfile (Worldfile *wf, int wf_entity)
bool Stalled () const
void Subscribe ()
void Unsubscribe ()
void VelocityDisable ()
void VelocityEnable ()
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 (ModelPtrSet &touchers)
void CommitTestedPose ()
ModelConditionalMove (const Pose &newpose)
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 GPoseDirtyTree ()
void Map ()
void MapFromRoot ()
void MapWithChildren ()
stg_meters_t ModelHeight () const
void PopCoords ()
void PushLocalCoords ()
void Raytrace (const stg_radians_t bearing, const stg_meters_t range, const stg_radians_t fov, const stg_ray_test_func_t func, const void *arg, stg_raytrace_result_t *samples, const uint32_t sample_count, const bool ztest=true)
stg_raytrace_result_t Raytrace (const stg_radians_t bearing, const stg_meters_t range, const stg_ray_test_func_t func, const void *arg, const bool ztest=true)
void Raytrace (const Pose &pose, const stg_meters_t range, const stg_radians_t fov, const stg_ray_test_func_t func, const void *arg, stg_raytrace_result_t *samples, const uint32_t sample_count, const bool ztest=true)
stg_raytrace_result_t Raytrace (const Pose &pose, const stg_meters_t range, const stg_ray_test_func_t func, const void *arg, const bool ztest=true)
void RegisterOption (Option *opt)
virtual void Shutdown ()
virtual void Startup ()
ModelTestCollision ()
ModelTestCollisionTree ()
void UnMap ()
void UnMapFromRoot ()
void UnMapWithChildren ()
virtual void Update ()
virtual void UpdateCharge ()
virtual void UpdatePose ()
void UpdateTrail ()

Protected Attributes

pthread_mutex_t access_mutex
 Used by Lock() and Unlock() to prevent parallel access to this model.
bool alwayson
BlockGroup blockgroup
int blocks_dl
int boundary
Color color
std::list< Visualizer * > cv_list
bool data_fresh
stg_bool_t disabled
 if non-zero, the model is disabled
unsigned int event_queue_num
std::list< Flag * > flag_list
double friction
Geom geom
class Stg::Model::GuiState gui
bool has_default_block
class Stg::Model::CallbackHooks hooks
uint32_t id
stg_usec_t interval
 time between updates in usec
stg_usec_t interval_energy
 time between updates of powerpack in usec
stg_usec_t interval_pose
 time between updates of pose due to velocity in usec
stg_usec_t last_update
 time of last update in us
bool log_state
 iff true, model state is logged
stg_meters_t map_resolution
stg_kg_t mass
Modelparent
Pose pose
PowerPackpower_pack
std::list< PowerPack * > pps_charging
std::map< std::string, const
void * > 
props
Stg::Model::RasterVis rastervis
bool rebuild_displaylist
 iff true, regenerate block display list before redraw
std::string say_string
 if non-null, this string is displayed in the GUI
stg_bool_t stall
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().
Velocity velocity
bool velocity_enable
stg_watts_t watts
 power consumed by this model
stg_watts_t watts_give
stg_watts_t watts_take
Worldfile * wf
int wf_entity
Worldworld
WorldGuiworld_gui

Static Protected Attributes

static std::map< void
*, std::set< stg_cb_t > > 
callbacks
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

Static Private Attributes

static uint32_t count
static std::map< stg_id_t,
Model * > 
modelsbyid

Friends

class Ancestor
class Block
class BlockGroup
class Canvas
class PowerPack
class Ray
class Region
class World
class World::Event
class WorldGui

Detailed Description

Model class

Definition at line 1579 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.

Stg::Model::Model ( World world,
Model parent = NULL,
const std::string &  type = "model" 
)

Constructor

virtual Stg::Model::~Model (  )  [virtual]

Destructor


Member Function Documentation

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

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

void Stg::Model::AddCallback ( void *  address,
stg_model_callback_t  cb,
void *  user 
)
void Stg::Model::AddFlag ( Flag flag  ) 
void Stg::Model::AddFlagDecrCallback ( stg_model_callback_t  cb,
void *  user 
) [inline]

Definition at line 2266 of file stage.hh.

void Stg::Model::AddFlagIncrCallback ( stg_model_callback_t  cb,
void *  user 
) [inline]

Definition at line 2260 of file stage.hh.

void Stg::Model::AddLoadCallback ( stg_model_callback_t  cb,
void *  user 
) [inline]

Definition at line 2242 of file stage.hh.

void Stg::Model::AddSaveCallback ( stg_model_callback_t  cb,
void *  user 
) [inline]

Definition at line 2248 of file stage.hh.

void Stg::Model::AddShutdownCallback ( stg_model_callback_t  cb,
void *  user 
) [inline]

Definition at line 2236 of file stage.hh.

void Stg::Model::AddStartupCallback ( stg_model_callback_t  cb,
void *  user 
) [inline]

Definition at line 2230 of file stage.hh.

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

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

void Stg::Model::AddToPose ( const Pose pose  ) 

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

void Stg::Model::AddUpdateCallback ( stg_model_callback_t  cb,
void *  user 
) [inline]

Definition at line 2254 of file stage.hh.

void Stg::Model::AddVisualizer ( Visualizer custom_visual,
bool  on_by_default 
)

Attach a user supplied visualization to a model.

void Stg::Model::AppendTouchingModels ( ModelPtrSet touchers  )  [protected]
void Stg::Model::BecomeParentOf ( Model child  ) 
int Stg::Model::CallCallbacks ( void *  address  ) 
void Stg::Model::ClearBlocks (  ) 

remove all blocks from this model, freeing their memory

void Stg::Model::CommitTestedPose (  )  [protected]
Model* Stg::Model::ConditionalMove ( const Pose newpose  )  [protected]
bool Stg::Model::DataIsFresh (  )  const [inline]

Definition at line 2213 of file stage.hh.

virtual void Stg::Model::DataVisualize ( Camera cam  )  [protected, virtual]
void Stg::Model::DataVisualizeTree ( Camera cam  )  [protected]
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 2072 of file stage.hh.

virtual void Stg::Model::DrawBlocks (  )  [protected, virtual]

Reimplemented in Stg::ModelLightIndicator.

void Stg::Model::DrawBlocksTree (  )  [protected]
void Stg::Model::DrawBoundingBox (  )  [protected]
void Stg::Model::DrawBoundingBoxTree (  )  [protected]
void Stg::Model::DrawFlagList (  )  [protected]
void Stg::Model::DrawGrid (  )  [protected]
void Stg::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

void Stg::Model::DrawOrigin (  )  [protected]
void Stg::Model::DrawOriginTree (  )  [protected]
virtual void Stg::Model::DrawPicker (  )  [protected, virtual]
void Stg::Model::DrawPose ( Pose  pose  )  [protected]
virtual void Stg::Model::DrawSelected ( void   )  [protected, virtual]
virtual void Stg::Model::DrawStatus ( Camera cam  )  [protected, virtual]
void Stg::Model::DrawStatusTree ( Camera cam  )  [protected]
void Stg::Model::DrawTrailArrows (  )  [protected]
void Stg::Model::DrawTrailBlocks (  )  [protected]
void Stg::Model::DrawTrailFootprint (  )  [protected]
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 2076 of file stage.hh.

PowerPack* Stg::Model::FindPowerPack (  )  const
Model* Stg::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.

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

Definition at line 2167 of file stage.hh.

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

Definition at line 1875 of file stage.hh.

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

Get a model's fiducial return value.

Definition at line 2161 of file stage.hh.

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

Definition at line 2066 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 2183 of file stage.hh.

Pose Stg::Model::GetGlobalPose (  )  const

get the pose of a model in the global CS

Velocity Stg::Model::GetGlobalVelocity (  )  const

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 2170 of file stage.hh.

stg_kg_t Stg::Model::GetMassOfChildren (  ) 

Get the mass of this model's children recursively.

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

Definition at line 1850 of file stage.hh.

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

Definition at line 1597 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 2187 of file stage.hh.

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

Definition at line 1876 of file stage.hh.

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

Definition at line 1851 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 2309 of file stage.hh.

stg_kg_t Stg::Model::GetTotalMass (  ) 

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

Model* Stg::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

Model* Stg::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.

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

Definition at line 1874 of file stage.hh.

Velocity Stg::Model::GetVelocity (  )  const [inline]

Get (a copy of) the model's velocity in its local reference frame.

Definition at line 2191 of file stage.hh.

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

Returns a pointer to the world that contains this model

Definition at line 2104 of file stage.hh.

Pose Stg::Model::GlobalToLocal ( const Pose pose  )  const

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

void Stg::Model::GPoseDirtyTree (  )  [protected]

Causes this model and its children to recompute their global position instead of using a cached pose in Model::GetGlobalPose()..

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

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

Definition at line 2312 of file stage.hh.

void Stg::Model::InitControllers (  ) 

Call Init() for all attached controllers.

bool Stg::Model::IsAntecedent ( const Model testmod  )  const
bool Stg::Model::IsDescendent ( const Model testmod  )  const

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

bool Stg::Model::IsRelated ( const Model testmod  )  const

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

virtual void Stg::Model::Load (  )  [virtual]
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 2039 of file stage.hh.

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

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

void Stg::Model::LoadControllerModule ( const char *  lib  ) 

Load a control program for this model from an external library

stg_point_t Stg::Model::LocalToGlobal ( const stg_point_t pt  )  const

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

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 2282 of file stage.hh.

void Stg::Model::LocalToPixels ( const std::vector< stg_point_t > &  local,
std::vector< stg_point_int_t > &  pixels 
) const

Fill an array of global pixels from an array of local points.

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

Look up a model pointer by a unique model ID

Definition at line 2018 of file stage.hh.

void Stg::Model::Map (  )  [protected]
void Stg::Model::MapFromRoot (  )  [protected]
void Stg::Model::MapWithChildren (  )  [protected]
stg_meters_t Stg::Model::ModelHeight (  )  const [protected]
void Stg::Model::NeedRedraw (  ) 

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

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 2101 of file stage.hh.

void Stg::Model::PlaceInFreeSpace ( stg_meters_t  xmin,
stg_meters_t  xmax,
stg_meters_t  ymin,
stg_meters_t  ymax 
)
virtual void Stg::Model::PopColor (  )  [inline, virtual]

Definition at line 2003 of file stage.hh.

void Stg::Model::PopCoords (  )  [protected]
Flag* Stg::Model::PopFlag (  ) 
std::string Stg::Model::PoseString (  )  [inline]

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

Definition at line 2014 of file stage.hh.

virtual void Stg::Model::Print ( char *  prefix  )  const [virtual]
virtual const char* Stg::Model::PrintWithPose (  )  const [virtual]
virtual void Stg::Model::PushColor ( double  r,
double  g,
double  b,
double  a 
) [inline, virtual]

Definition at line 2002 of file stage.hh.

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

Definition at line 2001 of file stage.hh.

void Stg::Model::PushFlag ( Flag flag  ) 
void Stg::Model::PushLocalCoords (  )  [protected]
void Stg::Model::Rasterize ( uint8_t *  data,
unsigned int  width,
unsigned int  height,
stg_meters_t  cellwidth,
stg_meters_t  cellheight 
)

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

void Stg::Model::Raytrace ( const stg_radians_t  bearing,
const stg_meters_t  range,
const stg_radians_t  fov,
const stg_ray_test_func_t  func,
const void *  arg,
stg_raytrace_result_t samples,
const uint32_t  sample_count,
const bool  ztest = true 
) [protected]
stg_raytrace_result_t Stg::Model::Raytrace ( const stg_radians_t  bearing,
const stg_meters_t  range,
const stg_ray_test_func_t  func,
const void *  arg,
const bool  ztest = true 
) [protected]
void Stg::Model::Raytrace ( const Pose pose,
const stg_meters_t  range,
const stg_radians_t  fov,
const stg_ray_test_func_t  func,
const void *  arg,
stg_raytrace_result_t 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

stg_raytrace_result_t Stg::Model::Raytrace ( const Pose pose,
const stg_meters_t  range,
const stg_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

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

Register an Option for pickup by the GUI.

int Stg::Model::RemoveCallback ( void *  member,
stg_model_callback_t  callback 
)
void Stg::Model::RemoveFlag ( Flag flag  ) 
void Stg::Model::RemoveFlagDecrCallback ( stg_model_callback_t  cb  )  [inline]

Definition at line 2269 of file stage.hh.

void Stg::Model::RemoveFlagIncrCallback ( stg_model_callback_t  cb  )  [inline]

Definition at line 2263 of file stage.hh.

void Stg::Model::RemoveLoadCallback ( stg_model_callback_t  cb  )  [inline]

Definition at line 2245 of file stage.hh.

void Stg::Model::RemoveSaveCallback ( stg_model_callback_t  cb  )  [inline]

Definition at line 2251 of file stage.hh.

void Stg::Model::RemoveShutdownCallback ( stg_model_callback_t  cb  )  [inline]

Definition at line 2239 of file stage.hh.

void Stg::Model::RemoveStartupCallback ( stg_model_callback_t  cb  )  [inline]

Definition at line 2233 of file stage.hh.

void Stg::Model::RemoveUpdateCallback ( stg_model_callback_t  cb  )  [inline]

Definition at line 2257 of file stage.hh.

void Stg::Model::RemoveVisualizer ( Visualizer custom_visual  ) 

remove user supplied visualization to a model - supply the same ptr passed to AddCustomVisualizer

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

return the root model of the tree containing this model

Definition at line 2107 of file stage.hh.

virtual void Stg::Model::Save (  )  [virtual]

save the state of the model to the current world file

Reimplemented in Stg::ModelGripper.

void Stg::Model::Say ( const std::string &  str  ) 
void Stg::Model::SetBlobReturn ( int  val  ) 
void Stg::Model::SetBoundary ( int  val  ) 
void Stg::Model::SetColor ( Color  col  ) 
void Stg::Model::SetFiducialKey ( int  key  ) 

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

void Stg::Model::SetFiducialReturn ( int  fid  ) 

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

void Stg::Model::SetFriction ( double  friction  ) 
void Stg::Model::SetGeom ( const Geom src  ) 

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

void Stg::Model::SetGlobalPose ( const Pose gpose  ) 

set the pose of model in global coordinates

void Stg::Model::SetGlobalVelocity ( const Velocity gvel  ) 
void Stg::Model::SetGravityReturn ( int  val  ) 
void Stg::Model::SetGripperReturn ( int  val  ) 
void Stg::Model::SetGuiGrid ( int  val  ) 
void Stg::Model::SetGuiMove ( int  val  ) 
void Stg::Model::SetGuiNose ( int  val  ) 
void Stg::Model::SetGuiOutline ( int  val  ) 
void Stg::Model::SetLaserReturn ( stg_laser_return_t  val  ) 
void Stg::Model::SetMapResolution ( stg_meters_t  res  ) 
void Stg::Model::SetMass ( stg_kg_t  mass  ) 
void Stg::Model::SetObstacleReturn ( int  val  ) 
int Stg::Model::SetParent ( Model newparent  ) 

Change a model's parent - experimental

void Stg::Model::SetPose ( const Pose pose  ) 

set a model's pose in its parent's coordinate system

void Stg::Model::SetRangerReturn ( int  val  ) 
void Stg::Model::SetStall ( stg_bool_t  stall  ) 
void Stg::Model::SetStickyReturn ( int  val  ) 
void Stg::Model::SetVelocity ( const Velocity vel  ) 

set a model's velocity in its parent's coordinate system

void Stg::Model::SetWatts ( stg_watts_t  watts  ) 
void Stg::Model::SetWorldfile ( Worldfile *  wf,
int  wf_entity 
) [inline]

Set the worldfile and worldfile entity ID

Definition at line 2048 of file stage.hh.

virtual void Stg::Model::Shutdown (  )  [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 2305 of file stage.hh.

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

subscribe to a model's data

Model* Stg::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.

Model* Stg::Model::TestCollisionTree (  )  [protected]

Recursively call TestCollision() on this model and all its descendents

void Stg::Model::UnMap (  )  [protected]
void Stg::Model::UnMapFromRoot (  )  [protected]
void Stg::Model::UnMapWithChildren (  )  [protected]
void Stg::Model::Unsubscribe (  ) 

unsubscribe from a model's data

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

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

void Stg::Model::VelocityDisable (  ) 

Disable update of model pose according to velocity state

void Stg::Model::VelocityEnable (  ) 

Enable update of model pose according to velocity state


Friends And Related Function Documentation

friend class Ancestor [friend]

Definition at line 1581 of file stage.hh.

friend class Block [friend]

Definition at line 1586 of file stage.hh.

friend class BlockGroup [friend]

Definition at line 1588 of file stage.hh.

friend class Canvas [friend]

Reimplemented from Stg::Ancestor.

Reimplemented in Stg::ModelPosition.

Definition at line 1585 of file stage.hh.

friend class PowerPack [friend]

Definition at line 1589 of file stage.hh.

friend class Ray [friend]

Definition at line 1590 of file stage.hh.

friend class Region [friend]

Definition at line 1587 of file stage.hh.

friend class World [friend]

Definition at line 1582 of file stage.hh.

friend class World::Event [friend]

Definition at line 1583 of file stage.hh.

friend class WorldGui [friend]

Definition at line 1584 of file stage.hh.


Member Data Documentation

pthread_mutex_t Stg::Model::access_mutex [protected]

Used by Lock() and Unlock() to prevent parallel access to this model.

Reimplemented from Stg::Ancestor.

Definition at line 1600 of file stage.hh.

bool Stg::Model::alwayson [protected]

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

Definition at line 1604 of file stage.hh.

Definition at line 1606 of file stage.hh.

int Stg::Model::blocks_dl [protected]

OpenGL display list identifier for the blockgroup

Definition at line 1608 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 1613 of file stage.hh.

std::map<void*, std::set<stg_cb_t> > Stg::Model::callbacks [static, 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 1660 of file stage.hh.

Color Stg::Model::color [protected]

Default color of the model's blocks.

Definition at line 1663 of file stage.hh.

uint32_t Stg::Model::count [static, private]

the number of models instatiated - used to assign unique IDs

Definition at line 1594 of file stage.hh.

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

Definition at line 1671 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 1669 of file stage.hh.

if non-zero, the model is disabled

Definition at line 1670 of file stage.hh.

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

Definition at line 1596 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 1824 of file stage.hh.

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

Definition at line 1672 of file stage.hh.

double Stg::Model::friction [protected]

Definition at line 1664 of file stage.hh.

Geom Stg::Model::geom [protected]

Definition at line 1673 of file stage.hh.

Records model state and functionality in the GUI, if used

Definition at line 1688 of file stage.hh.

uint32_t Stg::Model::id [protected]

unique process-wide identifier for this model

Definition at line 1722 of file stage.hh.

time between updates in usec

Definition at line 1723 of file stage.hh.

time between updates of powerpack in usec

Definition at line 1724 of file stage.hh.

time between updates of pose due to velocity in usec

Definition at line 1725 of file stage.hh.

time of last update in us

Definition at line 1727 of file stage.hh.

bool Stg::Model::log_state [protected]

iff true, model state is logged

Definition at line 1728 of file stage.hh.

Definition at line 1729 of file stage.hh.

Definition at line 1730 of file stage.hh.

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

Definition at line 1595 of file stage.hh.

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

Definition at line 2314 of file stage.hh.

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

Pointer to the parent of this model, possibly NULL.

Definition at line 1733 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 1737 of file stage.hh.

Optional attached PowerPack, defaults to NULL

Definition at line 1740 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 1744 of file stage.hh.

std::map<std::string,const void*> Stg::Model::props [protected]

Props map can contain arbitrary named data items. Can be used by derived model types to store properties, and for user code to associate arbitrary items with a model.

Definition at line 1749 of file stage.hh.

Visualize the most recent rasterization operation performed by this model

iff true, regenerate block display list before redraw

Definition at line 1779 of file stage.hh.

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

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

Definition at line 1780 of file stage.hh.

Definition at line 1782 of file stage.hh.

int Stg::Model::subs [protected]

the number of subscriptions to this model

Definition at line 1783 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

Definition at line 1786 of file stage.hh.

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

a ring buffer for storing recent poses

Definition at line 1804 of file stage.hh.

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

current position in the ring buffer

Definition at line 1807 of file stage.hh.

uint64_t Stg::Model::trail_interval [static, protected]

Number of world updates between trail records.

Definition at line 1815 of file stage.hh.

unsigned int Stg::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 1812 of file stage.hh.

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

Definition at line 1821 of file stage.hh.

bool Stg::Model::used [protected]

TRUE iff this model has been returned by GetUnusedModelOfType().

Definition at line 1825 of file stage.hh.

Definition at line 1826 of file stage.hh.

bool Stg::Model::velocity_enable [protected]

respond to velocity state by changing position. Initially false, set to true by subclass, worldfile, or explcicit call to Model::VelocityEnable().

Definition at line 1831 of file stage.hh.

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

power consumed by this model

Definition at line 1833 of file stage.hh.

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

Definition at line 1837 of file stage.hh.

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

Definition at line 1841 of file stage.hh.

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

Definition at line 1843 of file stage.hh.

int Stg::Model::wf_entity [protected]

Definition at line 1844 of file stage.hh.

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

Definition at line 1845 of file stage.hh.

Definition at line 1846 of file stage.hh.


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:39 2013