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

Model class More...

#include <stage.hh>

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

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

void 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 ()
 
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
 
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 HasCollision ()
 
bool HasSubscribers () const
 
void InitControllers ()
 
bool IsAntecedent (const Model *testmod) const
 
bool IsDescendent (const Model *testmod) const
 
bool IsEnabled () 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
 
bool PlaceInFreeSpace (meters_t xmin, meters_t xmax, meters_t ymin, meters_t ymax, size_t max_iter=0)
 
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)
 
bool RandomPoseInFreeSpace (meters_t xmin, meters_t xmax, meters_t ymin, meters_t ymax, size_t max_iter=0)
 
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 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 ()
 
- Public Member Functions inherited from Stg::Ancestor
virtual void AddChild (Model *mod)
 
 Ancestor ()
 
void ForEachDescendant (model_callback_t func, void *arg)
 
std::vector< Model * > & GetChildren ()
 
void * GetProperty (std::string &key)
 
virtual void RemoveChild (Model *mod)
 
void SetProperty (std::string &key, void *value)
 
const char * Token () const
 
const std::string & TokenStr () const
 
virtual ~Ancestor ()
 

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_tname_map
 

Protected Member Functions

void AppendTouchingModels (std::set< Model *> &touchers)
 
void CallUpdateCallbacks (void)
 
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)
 Find the root model, and map/unmap the whole tree. More...
 
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)
 
void Raytrace (const Pose &pose, const meters_t range, const radians_t fov, const ray_test_func_t func, const void *arg, const bool ztest, std::vector< RaytraceResult > &results)
 
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 ()
 
- Protected Member Functions inherited from Stg::Ancestor
AncestorLoad (Worldfile *wf, int section)
 
void Save (Worldfile *wf, int section)
 

Static Protected Member Functions

static int UpdateWrapper (Model *mod, void *)
 

Protected Attributes

bool alwayson
 
BlockGroup blockgroup
 
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 More...
 
usec_t interval_energy
 time between updates of powerpack in usec More...
 
usec_t last_update
 time of last update in us More...
 
bool log_state
 iff true, model state is logged More...
 
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 More...
 
std::string say_string
 if non-empty, this string is displayed in the GUI More...
 
bool stack_children
 whether child models should be stacked on top of this model or not More...
 
bool stall
 Set to true iff the model collided with something else. More...
 
int subs
 the number of subscriptions to this model More...
 
bool thread_safe
 
std::vector< TrailItemtrail
 
unsigned int trail_index
 
uint64_t trail_interval
 
const std::string type
 
bool used
 TRUE iff this model has been returned by GetUnusedModelOfType() More...
 
watts_t watts
 power consumed by this model More...
 
watts_t watts_give
 
watts_t watts_take
 
Worldfilewf
 
int wf_entity
 
Worldworld
 Pointer to the world in which this model exists. More...
 
WorldGuiworld_gui
 Pointer to the GUI world - NULL if running in non-gui mode. More...
 
- Protected Attributes inherited from Stg::Ancestor
std::map< std::string, unsigned int > child_type_counts
 
std::vector< Model * > children
 
bool debug
 
std::map< std::string, void * > props
 
std::string token
 

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

Member Enumeration Documentation

◆ callback_type_t

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 

must be the last entry: counts the number of types

Definition at line 1729 of file stage.hh.

Constructor & Destructor Documentation

◆ Model() [1/3]

Stg::Model::Model ( const Model original)
explicitprivate

Private copy constructor declared but not defined, to make it impossible to copy models.

◆ Model() [2/3]

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

Constructor

Definition at line 230 of file model.cc.

◆ ~Model()

Model::~Model ( void  )
virtual

Destructor

Definition at line 300 of file model.cc.

◆ Model() [3/3]

Stg::Model::Model ( )
inline

Alternate constructor that creates dummy models with only a pose

Definition at line 2100 of file stage.hh.

Member Function Documentation

◆ AddBlockRect()

void 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 378 of file model.cc.

◆ AddCallback()

void Model::AddCallback ( callback_type_t  type,
model_callback_t  cb,
void *  user 
)

attach callback functions to data members. The function gets called when the member is changed using SetX() accessor method 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 5 of file model_callbacks.cc.

◆ AddFlag()

void Model::AddFlag ( Flag flag)

Definition at line 323 of file model.cc.

◆ AddToPose() [1/2]

void Model::AddToPose ( const Pose pose)

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

Definition at line 638 of file model.cc.

◆ AddToPose() [2/2]

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 627 of file model.cc.

◆ AddVisualizer()

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

Attach a user supplied visualization to a model.

Definition at line 242 of file model_draw.cc.

◆ AppendTouchingModels()

void Model::AppendTouchingModels ( std::set< Model *> &  touchers)
protected

Definition at line 656 of file model.cc.

◆ BecomeParentOf()

void Model::BecomeParentOf ( Model child)

Definition at line 819 of file model.cc.

◆ CallCallbacks()

int Model::CallCallbacks ( callback_type_t  type)

Definition at line 32 of file model_callbacks.cc.

◆ CallUpdateCallbacks()

void Model::CallUpdateCallbacks ( void  )
protected

Calls CallCallback( CB_UPDATE )

Definition at line 612 of file model.cc.

◆ ClearBlocks()

void Model::ClearBlocks ( )

remove all blocks from this model, freeing their memory

Definition at line 360 of file model.cc.

◆ DataIsFresh()

bool Stg::Model::DataIsFresh ( ) const
inline

Definition at line 2271 of file stage.hh.

◆ DataVisualize()

void Model::DataVisualize ( Camera cam)
protectedvirtual

Reimplemented in Stg::ModelCamera, Stg::ModelBlinkenlight, Stg::ModelFiducial, and Stg::ModelGripper.

Definition at line 524 of file model_draw.cc.

◆ DataVisualizeTree()

void Model::DataVisualizeTree ( Camera cam)
protected

Definition at line 529 of file model_draw.cc.

◆ Disable()

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

◆ DrawBlocks()

void Model::DrawBlocks ( )
protectedvirtual

Reimplemented in Stg::ModelLightIndicator.

Definition at line 171 of file model_draw.cc.

◆ DrawBlocksTree()

void Model::DrawBlocksTree ( )
protected

Definition at line 148 of file model_draw.cc.

◆ DrawBoundingBox()

void Model::DrawBoundingBox ( )
protected

Definition at line 187 of file model_draw.cc.

◆ DrawBoundingBoxTree()

void Model::DrawBoundingBoxTree ( )
protected

Definition at line 176 of file model_draw.cc.

◆ DrawFlagList()

void Model::DrawFlagList ( void  )
protected

Definition at line 425 of file model_draw.cc.

◆ DrawGrid()

void Model::DrawGrid ( void  )
protected

Definition at line 550 of file model_draw.cc.

◆ DrawImage()

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 381 of file model_draw.cc.

◆ DrawOrigin()

void Stg::Model::DrawOrigin ( )
protected

◆ DrawOriginTree()

void Model::DrawOriginTree ( )
protected

Definition at line 140 of file model_draw.cc.

◆ DrawPicker()

void Model::DrawPicker ( void  )
protectedvirtual

Definition at line 509 of file model_draw.cc.

◆ DrawPose()

void Model::DrawPose ( Pose  pose)
protected

Definition at line 159 of file model_draw.cc.

◆ DrawSelected()

void Model::DrawSelected ( void  )
protectedvirtual

Definition at line 12 of file model_draw.cc.

◆ DrawStatus()

void Model::DrawStatus ( Camera cam)
protectedvirtual

Definition at line 282 of file model_draw.cc.

◆ DrawStatusTree()

void Model::DrawStatusTree ( Camera cam)
protected

Definition at line 273 of file model_draw.cc.

◆ DrawTrailArrows()

void Model::DrawTrailArrows ( )
protected

Definition at line 106 of file model_draw.cc.

◆ DrawTrailBlocks()

void Model::DrawTrailBlocks ( )
protected

Definition at line 86 of file model_draw.cc.

◆ DrawTrailFootprint()

void Model::DrawTrailFootprint ( )
protected

Definition at line 49 of file model_draw.cc.

◆ Enable()

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

◆ FindPowerPack()

PowerPack * Model::FindPowerPack ( ) const

Definition at line 833 of file model.cc.

◆ GetChild()

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 862 of file model.cc.

◆ GetColor()

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

Definition at line 2233 of file stage.hh.

◆ GetEnergyInterval()

usec_t Stg::Model::GetEnergyInterval ( ) const
inline

Definition at line 1940 of file stage.hh.

◆ GetFiducialReturn()

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

Get a model's fiducial return value.

Definition at line 2228 of file stage.hh.

◆ GetFlagCount()

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

Definition at line 2151 of file stage.hh.

◆ GetGeom()

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

◆ GetGlobalPose()

Pose Model::GetGlobalPose ( ) const
virtual

get the pose of a model in the global CS

Reimplemented from Stg::Ancestor.

Definition at line 1200 of file model.cc.

◆ GetId()

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

return a model's unique process-wide identifier

Definition at line 2235 of file stage.hh.

◆ GetInterval()

usec_t Stg::Model::GetInterval ( )
inline

return the update interval in usec

Definition at line 1923 of file stage.hh.

◆ GetMassOfChildren()

kg_t Model::GetMassOfChildren ( ) const

Get the mass of this model's children recursively.

Definition at line 803 of file model.cc.

◆ GetModelType()

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

Definition at line 1916 of file stage.hh.

◆ getOptions()

const std::vector<Option *>& Stg::Model::getOptions ( ) const
inlineprivate

Definition at line 1673 of file stage.hh.

◆ GetPose()

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

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

Definition at line 2250 of file stage.hh.

◆ GetSayString()

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

Definition at line 1917 of file stage.hh.

◆ GetSubscriptionCount()

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

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

Definition at line 2317 of file stage.hh.

◆ GetTotalMass()

kg_t Model::GetTotalMass ( ) const

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

Definition at line 793 of file model.cc.

◆ GetUnsubscribedModelOfType()

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 739 of file model.cc.

◆ GetUnusedModelOfType()

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 770 of file model.cc.

◆ GetUpdateInterval()

usec_t Stg::Model::GetUpdateInterval ( ) const
inline

Definition at line 1939 of file stage.hh.

◆ GetWorld()

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

Returns a pointer to the world that contains this model

Definition at line 2188 of file stage.hh.

◆ GlobalToLocal()

Pose Model::GlobalToLocal ( const Pose pose) const

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

Definition at line 398 of file model.cc.

◆ HasCollision()

bool Stg::Model::HasCollision ( )
inline

Check to see if the current pose causes a collision with obstacles. Returns true if a collision is detected but does not update the stall state, and false otherwise.

Definition at line 1951 of file stage.hh.

◆ HasSubscribers()

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

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

Definition at line 2319 of file stage.hh.

◆ InitControllers()

void Model::InitControllers ( )

Call Init() for all attached controllers.

Definition at line 318 of file model.cc.

◆ IsAntecedent()

bool Model::IsAntecedent ( const Model testmod) const

Definition at line 416 of file model.cc.

◆ IsDescendent()

bool Model::IsDescendent ( const Model testmod) const

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

Definition at line 428 of file model.cc.

◆ IsEnabled()

bool Stg::Model::IsEnabled ( ) const
inline

Test if the model is enabled. See also Disable() and Enable().

Definition at line 2161 of file stage.hh.

◆ IsRelated()

bool Model::IsRelated ( const Model testmod) const

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

Definition at line 441 of file model.cc.

◆ Load() [1/2]

void Stg::Model::Load ( Worldfile wf,
int  wf_entity 
)
inline

Set the worldfile and worldfile entity ID - must be called before Load()

Definition at line 2121 of file stage.hh.

◆ Load() [2/2]

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::ModelFiducial, Stg::ModelBumper, Stg::ModelGripper, and Stg::ModelBlobfinder.

Definition at line 1242 of file model.cc.

◆ LoadBlock()

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

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

Definition at line 368 of file model.cc.

◆ LoadControllerModule()

void Model::LoadControllerModule ( const char *  lib)

Load a control program for this model from an external library

Definition at line 1469 of file model.cc.

◆ LocalToGlobal() [1/2]

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

◆ LocalToGlobal() [2/2]

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 463 of file model.cc.

◆ LocalToPixels()

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 469 of file model.cc.

◆ LookupId()

static Model* Stg::Model::LookupId ( uint32_t  id)
inlinestatic

Look up a model pointer by a unique model ID

Definition at line 2091 of file stage.hh.

◆ Map() [1/2]

void Model::Map ( unsigned int  layer)
protected

Definition at line 809 of file model.cc.

◆ Map() [2/2]

void Stg::Model::Map ( )
inlineprotected

Call Map on all layers

Definition at line 1976 of file stage.hh.

◆ MapFromRoot()

void Model::MapFromRoot ( unsigned int  layer)
protected

Find the root model, and map/unmap the whole tree.

Definition at line 497 of file model.cc.

◆ MapWithChildren()

void Model::MapWithChildren ( unsigned int  layer)
protected

Definition at line 488 of file model.cc.

◆ ModelHeight()

meters_t Model::ModelHeight ( ) const
protected

Definition at line 617 of file model.cc.

◆ NeedRedraw()

void Model::NeedRedraw ( void  )

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

Definition at line 755 of file model.cc.

◆ operator=()

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

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

◆ Parent()

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

◆ PlaceInFreeSpace()

bool Stg::Model::PlaceInFreeSpace ( meters_t  xmin,
meters_t  xmax,
meters_t  ymin,
meters_t  ymax,
size_t  max_iter = 0 
)

Ensures that the model is placed in free space (w/o collisions). The pose is not altered if the model is already in free space. Since this is implemented in a set-and-test manner, you can provide a maximum number of tries to prevent running indefinitely.

Parameters
xminminimum x position for the model
xmaxmaximum x position for the model
yminminimum y position for the model
ymaxmaximum x position for the model
max_itermaximum number of iterations, 0 to possibly run/try indefinitely
Returns
true on success, false otherwise (no pose found within max_iter)

◆ PopColor()

virtual void Stg::Model::PopColor ( )
inlinevirtual

Definition at line 2061 of file stage.hh.

◆ PopCoords()

void Model::PopCoords ( )
protected

Definition at line 237 of file model_draw.cc.

◆ PopFlag()

Model::Flag * Model::PopFlag ( )

Definition at line 347 of file model.cc.

◆ PoseString()

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

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

Definition at line 2089 of file stage.hh.

◆ Print()

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

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

Definition at line 542 of file model.cc.

◆ PrintWithPose()

const char * Model::PrintWithPose ( ) const
virtual

Definition at line 555 of file model.cc.

◆ PushColor() [1/2]

virtual void Stg::Model::PushColor ( Color  col)
inlinevirtual

Definition at line 2059 of file stage.hh.

◆ PushColor() [2/2]

virtual void Stg::Model::PushColor ( double  r,
double  g,
double  b,
double  a 
)
inlinevirtual

Definition at line 2060 of file stage.hh.

◆ PushFlag()

void Model::PushFlag ( Flag flag)

Definition at line 339 of file model.cc.

◆ PushLocalCoords()

void Model::PushLocalCoords ( )
protected

Definition at line 227 of file model_draw.cc.

◆ RandomPoseInFreeSpace()

bool Model::RandomPoseInFreeSpace ( meters_t  xmin,
meters_t  xmax,
meters_t  ymin,
meters_t  ymax,
size_t  max_iter = 0 
)

Behaves much like PlaceInFreeSpace() but always changes the pose to a random one. Ensures that the model is placed in free space (w/o collisions). The pose is not altered if the model is already in free space. Since this is implemented in a set-and-test manner, you can provide a maximum number of tries to prevent running indefinitely.

Parameters
xminminimum x position for the model
xmaxmaximum x position for the model
yminminimum y position for the model
ymaxmaximum x position for the model
max_itermaximum number of iterations, 0 to possibly run/try indefinitely
Returns
true on success, false otherwise (no pose found within max_iter)

Definition at line 644 of file model.cc.

◆ Rasterize()

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 849 of file model.cc.

◆ Raytrace() [1/2]

RaytraceResult Stg::Model::Raytrace ( const Pose pose,
const meters_t  range,
const ray_test_func_t  func,
const void *  arg,
const bool  ztest 
)
inlineprotected

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

Definition at line 2000 of file stage.hh.

◆ Raytrace() [2/2]

void Stg::Model::Raytrace ( const Pose pose,
const meters_t  range,
const radians_t  fov,
const ray_test_func_t  func,
const void *  arg,
const bool  ztest,
std::vector< RaytraceResult > &  results 
)
inlineprotected

raytraces multiple rays around the point and heading identified by pose, in local coords

Definition at line 2008 of file stage.hh.

◆ Redraw()

void Model::Redraw ( void  )

Force the GUI (if any) to redraw this model

Definition at line 765 of file model.cc.

◆ RegisterOption()

void Model::RegisterOption ( Option opt)
protected

Register an Option for pickup by the GUI.

Definition at line 844 of file model.cc.

◆ RemoveCallback()

int Model::RemoveCallback ( callback_type_t  type,
model_callback_t  callback 
)

Definition at line 17 of file model_callbacks.cc.

◆ RemoveFlag()

void Model::RemoveFlag ( Flag flag)

Definition at line 331 of file model.cc.

◆ RemoveVisualizer()

void Model::RemoveVisualizer ( Visualizer custom_visual)

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

Definition at line 264 of file model_draw.cc.

◆ Root()

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

return the root model of the tree containing this model

Definition at line 2190 of file stage.hh.

◆ Save()

void Model::Save ( void  )
virtual

save the state of the model to the current world file

Reimplemented in Stg::ModelGripper.

Definition at line 1435 of file model.cc.

◆ Say()

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

Definition at line 410 of file model.cc.

◆ SetBlobReturn()

void Model::SetBlobReturn ( bool  val)

Definition at line 1124 of file model.cc.

◆ SetBoundary()

void Model::SetBoundary ( bool  val)

Definition at line 1134 of file model.cc.

◆ SetColor()

void Model::SetColor ( Color  col)

Definition at line 1081 of file model.cc.

◆ SetFiducialKey()

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 1114 of file model.cc.

◆ SetFiducialReturn()

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 1102 of file model.cc.

◆ SetFriction()

void Model::SetFriction ( double  friction)

Definition at line 857 of file model.cc.

◆ SetGeom()

void Model::SetGeom ( const Geom src)

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

Definition at line 1061 of file model.cc.

◆ SetGlobalPose()

void Model::SetGlobalPose ( const Pose gpose)

set the pose of model in global coordinates

Definition at line 1170 of file model.cc.

◆ SetGravityReturn()

void Stg::Model::SetGravityReturn ( bool  val)

◆ SetGripperReturn()

void Model::SetGripperReturn ( bool  val)

Definition at line 1097 of file model.cc.

◆ SetGuiGrid()

void Model::SetGuiGrid ( bool  val)

Definition at line 1149 of file model.cc.

◆ SetGuiMove()

void Model::SetGuiMove ( bool  val)

Definition at line 1144 of file model.cc.

◆ SetGuiNose()

void Model::SetGuiNose ( bool  val)

Definition at line 1139 of file model.cc.

◆ SetGuiOutline()

void Model::SetGuiOutline ( bool  val)

Definition at line 1154 of file model.cc.

◆ SetMapResolution()

void Model::SetMapResolution ( meters_t  res)

Definition at line 1164 of file model.cc.

◆ SetMass()

void Model::SetMass ( kg_t  mass)

Definition at line 1087 of file model.cc.

◆ SetObstacleReturn()

void Model::SetObstacleReturn ( bool  val)

Definition at line 1119 of file model.cc.

◆ SetParent()

int Model::SetParent ( Model newparent)

Change a model's parent - experimental

Definition at line 1175 of file model.cc.

◆ SetPose()

void Model::SetPose ( const Pose pose)

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

Definition at line 1216 of file model.cc.

◆ SetRangerReturn() [1/2]

void Model::SetRangerReturn ( double  val)

Definition at line 1129 of file model.cc.

◆ SetRangerReturn() [2/2]

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

◆ SetStall()

void Model::SetStall ( bool  stall)

Definition at line 1092 of file model.cc.

◆ SetStickyReturn()

void Stg::Model::SetStickyReturn ( bool  val)

◆ SetToken()

virtual void Stg::Model::SetToken ( const std::string &  str)
inlinevirtual

Reimplemented from Stg::Ancestor.

Definition at line 1905 of file stage.hh.

◆ SetWatts()

void Model::SetWatts ( watts_t  watts)

Definition at line 1159 of file model.cc.

◆ SetWorldfile()

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

Set the worldfile and worldfile entity ID

Definition at line 2130 of file stage.hh.

◆ Shutdown()

void Model::Shutdown ( void  )
protectedvirtual

◆ Stalled()

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

◆ Startup()

void Model::Startup ( void  )
protectedvirtual

◆ Subscribe()

void Model::Subscribe ( void  )

subscribe to a model's data

Definition at line 516 of file model.cc.

◆ TestCollision()

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 661 of file model.cc.

◆ UnMap() [1/2]

void Model::UnMap ( unsigned int  layer)
protected

Definition at line 814 of file model.cc.

◆ UnMap() [2/2]

void Stg::Model::UnMap ( )
inlineprotected

Call UnMap on all layers

Definition at line 1985 of file stage.hh.

◆ UnMapFromRoot()

void Model::UnMapFromRoot ( unsigned int  layer)
protected

Definition at line 511 of file model.cc.

◆ UnMapWithChildren()

void Model::UnMapWithChildren ( unsigned int  layer)
protected

Definition at line 502 of file model.cc.

◆ Unsubscribe()

void Model::Unsubscribe ( void  )

unsubscribe from a model's data

Definition at line 529 of file model.cc.

◆ Update()

void Model::Update ( void  )
protectedvirtual

◆ UpdateCharge()

void Model::UpdateCharge ( )
protectedvirtual

Definition at line 676 of file model.cc.

◆ UpdateTrail()

void Model::UpdateTrail ( )
protected

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

Definition at line 725 of file model.cc.

◆ UpdateWrapper()

static int Stg::Model::UpdateWrapper ( Model mod,
void *   
)
inlinestaticprotected

Definition at line 2017 of file stage.hh.

Friends And Related Function Documentation

◆ Ancestor

friend class Ancestor
friend

Definition at line 1652 of file stage.hh.

◆ Block

friend class Block
friend

Definition at line 1657 of file stage.hh.

◆ BlockGroup

friend class BlockGroup
friend

Definition at line 1659 of file stage.hh.

◆ Canvas

friend class Canvas
friend

Definition at line 1656 of file stage.hh.

◆ ModelFiducial

friend class ModelFiducial
friend

Definition at line 1662 of file stage.hh.

◆ PowerPack

friend class PowerPack
friend

Definition at line 1660 of file stage.hh.

◆ Ray

friend class Ray
friend

Definition at line 1661 of file stage.hh.

◆ Region

friend class Region
friend

Definition at line 1658 of file stage.hh.

◆ World

friend class World
friend

Definition at line 1653 of file stage.hh.

◆ World::Event

friend class World::Event
friend

Definition at line 1654 of file stage.hh.

◆ WorldGui

friend class WorldGui
friend

Definition at line 1655 of file stage.hh.

Member Data Documentation

◆ alwayson

bool Stg::Model::alwayson
protected

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

Definition at line 1677 of file stage.hh.

◆ blockgroup

BlockGroup Stg::Model::blockgroup
protected

Definition at line 1679 of file stage.hh.

◆ boundary

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

◆ callbacks

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

◆ color

Color Stg::Model::color
protected

Default color of the model's blocks.

Definition at line 1753 of file stage.hh.

◆ count

uint32_t Model::count
staticprivate

the number of models instatiated - used to assign unique sequential IDs

Definition at line 1666 of file stage.hh.

◆ cv_list

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

Container for Visualizers attached to this model.

Definition at line 1766 of file stage.hh.

◆ data_fresh

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

◆ disabled

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

◆ drawOptions

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

Definition at line 1672 of file stage.hh.

◆ event_queue_num

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

◆ flag_list

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

Container for flags attached to this model.

Definition at line 1769 of file stage.hh.

◆ friction

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

◆ geom

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

◆ gui

class Stg::Model::GuiState Stg::Model::gui
protected

◆ has_default_block

bool Stg::Model::has_default_block
protected

Definition at line 1791 of file stage.hh.

◆ id

uint32_t Stg::Model::id
protected

unique process-wide identifier for this model

Definition at line 1794 of file stage.hh.

◆ interval

usec_t Stg::Model::interval
protected

time between updates in usec

Definition at line 1795 of file stage.hh.

◆ interval_energy

usec_t Stg::Model::interval_energy
protected

time between updates of powerpack in usec

Definition at line 1796 of file stage.hh.

◆ last_update

usec_t Stg::Model::last_update
protected

time of last update in us

Definition at line 1797 of file stage.hh.

◆ log_state

bool Stg::Model::log_state
protected

iff true, model state is logged

Definition at line 1798 of file stage.hh.

◆ map_resolution

meters_t Stg::Model::map_resolution
protected

Definition at line 1799 of file stage.hh.

◆ mapped

bool Stg::Model::mapped
private

records if this model has been mapped into the world bitmap

Definition at line 1670 of file stage.hh.

◆ mass

kg_t Stg::Model::mass
protected

Definition at line 1800 of file stage.hh.

◆ modelsbyid

std::map< Stg::id_t, Model * > Model::modelsbyid
staticprivate

Definition at line 1667 of file stage.hh.

◆ name_map

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

Definition at line 2320 of file stage.hh.

◆ parent

Model* Stg::Model::parent
protected

Pointer to the parent of this model, possibly NULL.

Definition at line 1803 of file stage.hh.

◆ pose

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

◆ power_pack

PowerPack* Stg::Model::power_pack
protected

Optional attached PowerPack, defaults to NULL

Definition at line 1810 of file stage.hh.

◆ pps_charging

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

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

Definition at line 1814 of file stage.hh.

◆ rastervis

Stg::Model::RasterVis Stg::Model::rastervis
protected

◆ rebuild_displaylist

bool Stg::Model::rebuild_displaylist
protected

iff true, regenerate block display list before redraw

Definition at line 1840 of file stage.hh.

◆ say_string

std::string Stg::Model::say_string
protected

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

Definition at line 1841 of file stage.hh.

◆ stack_children

bool Stg::Model::stack_children
protected

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

Definition at line 1843 of file stage.hh.

◆ stall

bool Stg::Model::stall
protected

Set to true iff the model collided with something else.

Definition at line 1845 of file stage.hh.

◆ subs

int Stg::Model::subs
protected

the number of subscriptions to this model

Definition at line 1846 of file stage.hh.

◆ thread_safe

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

◆ trail

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

a ring buffer for storing recent poses

Definition at line 1866 of file stage.hh.

◆ trail_index

unsigned int Stg::Model::trail_index
protected

current position in the ring buffer

Definition at line 1869 of file stage.hh.

◆ trail_interval

uint64_t Stg::Model::trail_interval
protected

The maxiumum length of the trail drawn. Default is 20, but can be set in the world file using the trail_length model property. Number of world updates between trail records.

Definition at line 1877 of file stage.hh.

◆ type

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

Definition at line 1883 of file stage.hh.

◆ used

bool Stg::Model::used
protected

TRUE iff this model has been returned by GetUnusedModelOfType()

Definition at line 1887 of file stage.hh.

◆ vis

class Stg::Model::Visibility Stg::Model::vis

◆ watts

watts_t Stg::Model::watts
protected

power consumed by this model

Definition at line 1889 of file stage.hh.

◆ watts_give

watts_t Stg::Model::watts_give
protected

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

Definition at line 1893 of file stage.hh.

◆ watts_take

watts_t Stg::Model::watts_take
protected

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

Definition at line 1897 of file stage.hh.

◆ wf

Worldfile* Stg::Model::wf
protected

Definition at line 1899 of file stage.hh.

◆ wf_entity

int Stg::Model::wf_entity
protected

Definition at line 1900 of file stage.hh.

◆ world

World* Stg::Model::world
protected

Pointer to the world in which this model exists.

Definition at line 1901 of file stage.hh.

◆ world_gui

WorldGui* Stg::Model::world_gui
protected

Pointer to the GUI world - NULL if running in non-gui mode.

Definition at line 1902 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 Mon Feb 28 2022 23:48:56