World class More...
#include <stage.hh>

Classes | |
| class | Event |
| struct | ltx |
| struct | lty |
Public Member Functions | |
| virtual void | AddModel (Model *mod) |
| void | AddModelName (Model *mod, const std::string &name) |
| void | AddPowerPack (PowerPack *pp) |
| SuperRegion * | AddSuperRegion (const point_int_t &coord) |
| void | AddUpdateCallback (world_callback_t cb, void *user) |
| void | CancelQuit () |
| void | CancelQuitAll () |
| void | ClearRays () |
| virtual std::string | ClockString (void) const |
| void | ConsumeQueue (unsigned int queue_num) |
| Model * | CreateModel (Model *parent, const std::string &typestr) |
| SuperRegion * | CreateSuperRegion (point_int_t origin) |
| void | DestroySuperRegion (SuperRegion *sr) |
| void | DisableEnergy (Model *m) |
| void | EnableEnergy (Model *m) |
| void | Enqueue (unsigned int queue_num, usec_t delay, Model *mod, model_callback_t cb, void *arg) |
| void | Extend (point3_t pt) |
| const std::set< Model * > | GetAllModels () const |
| unsigned int | GetEventQueue (Model *mod) const |
| const bounds3d_t & | GetExtent () const |
| Model * | GetGround () |
| Model * | GetModel (const std::string &name) const |
| SuperRegion * | GetSuperRegion (const point_int_t &org) |
| SuperRegion * | GetSuperRegionCreate (const point_int_t &org) |
| uint64_t | GetUpdateCount () const |
| Worldfile * | GetWorldFile () |
| virtual bool | IsGUI () const |
| virtual void | Load (const std::string &worldfile_path) |
| void | LoadBlock (Worldfile *wf, int entity) |
| void | LoadBlockGroup (Worldfile *wf, int entity) |
| void | LoadModel (Worldfile *wf, int entity) |
| void | LoadSensor (Worldfile *wf, int entity) |
| void | Log (Model *mod) |
| void | MapPoly (const std::vector< point_int_t > &poly, Block *block, unsigned int layer) |
| int32_t | MetersToPixels (meters_t x) const |
| point_int_t | MetersToPixels (const point_t &pt) const |
| void | NeedRedraw () |
| bool | PastQuitTime () |
| bool | Paused () const |
| virtual void | PopColor () |
| virtual void | PushColor (Color col) |
| virtual void | PushColor (double r, double g, double b, double a) |
| void | Quit () |
| void | QuitAll () |
| RaytraceResult | Raytrace (const Ray &ray) |
| RaytraceResult | Raytrace (const Pose &pose, const meters_t range, const ray_test_func_t func, const Model *finder, 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 Model *finder, const void *arg, RaytraceResult *samples, const uint32_t sample_count, const bool ztest) |
| virtual Model * | RecentlySelectedModel () const |
| void | RecordRay (double x1, double y1, double x2, double y2) |
| virtual void | Redraw (void) |
| void | RegisterOption (Option *opt) |
| Register an Option for pickup by the GUI. More... | |
| virtual void | Reload () |
| virtual void | RemoveModel (Model *mod) |
| void | RemovePowerPack (PowerPack *pp) |
| int | RemoveUpdateCallback (world_callback_t cb, void *user) |
| double | Resolution () const |
| virtual bool | Save (const char *filename) |
| void | ShowClock (bool enable) |
| Control printing time to stdout. More... | |
| usec_t | SimTimeNow (void) const |
| virtual void | Start () |
| virtual void | Stop () |
| bool | TestQuit () const |
| virtual void | TogglePause () |
| void | TryCharge (PowerPack *pp, const Pose &pose) |
| virtual void | UnLoad () |
| virtual bool | Update (void) |
| uint64_t | UpdateCount () |
| World (const std::string &name="MyWorld", double ppm=DEFAULT_PPM) | |
| virtual | ~World () |
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 () |
| virtual Pose | GetGlobalPose () const |
| void * | GetProperty (std::string &key) |
| virtual void | RemoveChild (Model *mod) |
| void | SetProperty (std::string &key, void *value) |
| virtual void | SetToken (const std::string &str) |
| const char * | Token () const |
| const std::string & | TokenStr () const |
| virtual | ~Ancestor () |
Static Public Member Functions | |
| static void | Run () |
| static void * | update_thread_entry (std::pair< World *, int > *info) |
| static bool | UpdateAll () |
Public Attributes | |
| std::set< Model * > | active_energy |
| std::set< ModelPosition * > | active_velocity |
| std::vector< std::priority_queue< Event > > | event_queues |
| Model * | ground |
| bool | paused |
| if true, the simulation is stopped More... | |
| std::vector< std::queue< Model * > > | pending_update_callbacks |
| std::vector< point_int_t > | rt_candidate_cells |
| std::vector< point_int_t > | rt_cells |
| usec_t | sim_interval |
| int | update_cb_count |
Static Public Attributes | |
| static std::vector< std::string > | args |
| static std::string | ctrlargs |
| static const int | DEFAULT_PPM = 50 |
Protected Member Functions | |
| void | CallUpdateCallbacks () |
| Call all calbacks in cb_list, removing any that return true;. More... | |
Protected Member Functions inherited from Stg::Ancestor | |
| Ancestor & | Load (Worldfile *wf, int section) |
| void | Save (Worldfile *wf, int section) |
Protected Attributes | |
| std::list< std::pair< world_callback_t, void * > > | cb_list |
| List of callback functions and arguments. More... | |
| bounds3d_t | extent |
| Describes the 3D volume of the world. More... | |
| bool | graphics |
| true iff we have a GUI More... | |
| std::set< Option * > | option_table |
| GUI options (toggles) registered by models. More... | |
| std::list< PowerPack * > | powerpack_list |
| List of all the powerpacks attached to models in the world. More... | |
| usec_t | quit_time |
| std::list< float * > | ray_list |
| List of rays traced for debug visualization. More... | |
| usec_t | sim_time |
| the current sim time in this world in microseconds More... | |
| std::map< point_int_t, SuperRegion * > | superregions |
| std::vector< std::vector< Model * > > | update_lists |
| uint64_t | updates |
| the number of simulated time steps executed so far More... | |
| Worldfile * | wf |
| If set, points to the worldfile used to create this world. 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 | |
| void | FiducialErase (Model *mod) |
| void | FiducialInsert (Model *mod) |
Static Private Member Functions | |
| static void | UpdateCb (World *world) |
Private Attributes | |
| bool | destroy |
| bool | dirty |
| iff true, a gui redraw would be required More... | |
| std::set< Model * > | models |
| std::map< std::string, Model * > | models_by_name |
| std::map< int, Model * > | models_by_wfentity |
| std::vector< Model * > | models_with_fiducials |
| std::set< Model *, ltx > | models_with_fiducials_byx |
| std::set< Model *, lty > | models_with_fiducials_byy |
| double | ppm |
| the resolution of the world model in pixels per meter More... | |
| bool | quit |
| quit this world ASAP More... | |
| bool | show_clock |
| iff true, print the sim time on stdout More... | |
| unsigned int | show_clock_interval |
| updates between clock outputs More... | |
| pthread_mutex_t | sync_mutex |
| protect the worker thread management stuff More... | |
| pthread_cond_t | threads_done_cond |
| signalled by last worker thread to unblock main thread More... | |
| pthread_cond_t | threads_start_cond |
| signalled to unblock worker threads More... | |
| unsigned int | threads_working |
| the number of worker threads not yet finished More... | |
| int | total_subs |
| the total number of subscriptions to all models More... | |
| unsigned int | worker_threads |
| the number of worker threads to use More... | |
Static Private Attributes | |
| static unsigned int | next_id |
| initially zero, used to allocate unique sequential world ids More... | |
| static bool | quit_all |
| quit all worlds ASAP More... | |
| static std::set< World * > | world_set |
| all the worlds that exist More... | |
Friends | |
| class | Block |
| class | Canvas |
| class | Model |
| class | ModelFiducial |
| class | WorkerThread |
| World::World | ( | const std::string & | name = "MyWorld", |
| double | ppm = DEFAULT_PPM |
||
| ) |
|
virtual |
Reimplemented in Stg::WorldGui.
| void World::AddModelName | ( | Model * | mod, |
| const std::string & | name | ||
| ) |
| SuperRegion * World::AddSuperRegion | ( | const point_int_t & | coord | ) |
| void World::AddUpdateCallback | ( | world_callback_t | cb, |
| void * | user | ||
| ) |
|
protected |
|
inline |
|
inline |
|
virtual |
Get human readable string that describes the current simulation time.
Reimplemented in Stg::WorldGui.
| void World::ConsumeQueue | ( | unsigned int | queue_num | ) |
| SuperRegion * World::CreateSuperRegion | ( | point_int_t | origin | ) |
| void World::DestroySuperRegion | ( | SuperRegion * | sr | ) |
|
inline |
Create a new simulation event to be handled in the future.
| queue_num | Specify which queue the event should be on. The main thread is 0. |
| delay | The time from now until the event occurs, in microseconds. |
| mod | The model that should have its Update() method called at the specified time. |
|
inline |
|
inlineprivate |
|
inlineprivate |
|
inline |
| unsigned int World::GetEventQueue | ( | Model * | mod | ) | const |
|
inline |
|
inline |
| Model * World::GetModel | ( | const std::string & | name | ) | const |
|
inline |
|
inline |
|
inline |
|
inline |
|
inlinevirtual |
Returns true iff this World implements a GUI. The base World class returns false, but subclasses can override this behaviour.
Reimplemented in Stg::WorldGui.
|
virtual |
Open the file at the specified location, create a Worldfile object, read the file and configure the world from the contents, creating models as necessary. The created object persists, and can be retrieved later with World::GetWorldFile().
Reimplemented in Stg::WorldGui.
| void Stg::World::LoadBlockGroup | ( | Worldfile * | wf, |
| int | entity | ||
| ) |
| void World::MapPoly | ( | const std::vector< point_int_t > & | poly, |
| Block * | block, | ||
| unsigned int | layer | ||
| ) |
|
inline |
|
inline |
|
inline |
| bool World::PastQuitTime | ( | ) |
|
inlinevirtual |
Reimplemented in Stg::WorldGui.
|
inlinevirtual |
Reimplemented in Stg::WorldGui.
|
inlinevirtual |
Reimplemented in Stg::WorldGui.
|
inline |
|
inline |
| RaytraceResult World::Raytrace | ( | const Ray & | ray | ) |
| RaytraceResult World::Raytrace | ( | const Pose & | pose, |
| const meters_t | range, | ||
| const ray_test_func_t | func, | ||
| const Model * | finder, | ||
| const void * | arg, | ||
| const bool | ztest | ||
| ) |
| void World::Raytrace | ( | const Pose & | pose, |
| const meters_t | range, | ||
| const radians_t | fov, | ||
| const ray_test_func_t | func, | ||
| const Model * | finder, | ||
| const void * | arg, | ||
| RaytraceResult * | samples, | ||
| const uint32_t | sample_count, | ||
| const bool | ztest | ||
| ) |
|
inlinevirtual |
Reimplemented in Stg::WorldGui.
| void World::RecordRay | ( | double | x1, |
| double | y1, | ||
| double | x2, | ||
| double | y2 | ||
| ) |
|
inlinevirtual |
Force the GUI to redraw the world, even if paused. This imlementation does nothing, but can be overridden by subclasses.
Reimplemented in Stg::WorldGui.
| void World::RegisterOption | ( | Option * | opt | ) |
| int World::RemoveUpdateCallback | ( | world_callback_t | cb, |
| void * | user | ||
| ) |
|
inline |
|
static |
run all worlds. If only non-gui worlds were created, UpdateAll() is repeatedly called. To simulate a gui world only a single gui world may have been created. This world is then simulated.
|
virtual |
Save the current world state into a worldfile with the given filename.
| Filename | to save as. |
Reimplemented in Stg::WorldGui.
|
inline |
|
inline |
|
inlinevirtual |
Reimplemented in Stg::WorldGui.
|
inlinevirtual |
Reimplemented in Stg::WorldGui.
|
inline |
|
virtual |
Reimplemented in Stg::WorldGui.
|
virtual |
Run one simulation timestep. Advances the simulation clock, executes all simulation updates due at the current time, then queues up future events.
Reimplemented in Stg::WorldGui.
|
static |
|
static |
|
staticprivate |
|
friend |
| std::set<Model*> Stg::World::active_energy |
Set of models that require energy calculations at each World::Update().
| std::set<ModelPosition*> Stg::World::active_velocity |
Set of models that require their positions to be recalculated at each World::Update().
|
static |
contains the command line arguments passed to Stg::Init(), so that controllers can read them.
|
protected |
|
private |
| std::vector<std::priority_queue<Event> > Stg::World::event_queues |
|
protected |
| Model* Stg::World::ground |
|
private |
|
private |
|
private |
|
private |
|
staticprivate |
|
protected |
| std::vector<std::queue<Model*> > Stg::World::pending_update_callbacks |
|
protected |
|
private |
|
protected |
World::quit is set true when this simulation time is reached
|
protected |
| std::vector<point_int_t> Stg::World::rt_candidate_cells |
| std::vector<point_int_t> Stg::World::rt_cells |
|
private |
|
private |
| usec_t Stg::World::sim_interval |
|
protected |
|
protected |
|
private |
|
private |
|
private |
|
private |
|
private |
|
protected |
|
protected |
|
protected |
|
private |
|
staticprivate |