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

Classes | |
class | Event |
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 bool | Load (const std::string &worldfile_path) |
virtual bool | Load (std::istream &world_content, const std::string &worldfile_path=std::string()) |
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) |
point_int_t | MetersToPixels (const point_t &pt) const |
int32_t | MetersToPixels (meters_t x) const |
void | NeedRedraw () |
bool | PastQuitTime () |
bool | Paused () const |
virtual void | PopColor () |
virtual void | PushColor (Color col) |
dummy implementations to be overloaded by GUI subclasses | |
virtual void | PushColor (double r, double g, double b, double a) |
void | Quit () |
void | QuitAll () |
void | Raytrace (const Pose &gpose, const meters_t range, const radians_t fov, const ray_test_func_t func, const Model *model, const void *arg, const bool ztest, std::vector< RaytraceResult > &results) |
RaytraceResult | Raytrace (const Pose &pose, const meters_t range, const ray_test_func_t func, const Model *finder, const void *arg, const bool ztest) |
RaytraceResult | Raytrace (const Ray &ray) |
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. | |
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. | |
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 () |
![]() | |
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 | |
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;. | |
![]() | |
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. | |
bounds3d_t | extent |
Describes the 3D volume of the world. | |
bool | graphics |
true iff we have a GUI | |
std::set< Option * > | option_table |
GUI options (toggles) registered by models. | |
std::list< PowerPack * > | powerpack_list |
List of all the powerpacks attached to models in the world. | |
usec_t | quit_time |
std::list< float * > | ray_list |
List of rays traced for debug visualization. | |
usec_t | sim_time |
the current sim time in this world in microseconds | |
std::map< point_int_t, SuperRegion * > | superregions |
uint64_t | updates |
the number of simulated time steps executed so far | |
Worldfile * | wf |
If set, points to the worldfile used to create this world. | |
![]() | |
std::map< std::string, unsigned int > | child_type_counts |
std::vector< Model * > | children |
bool | debug |
std::map< std::string, void * > | props |
std::string | token |
Detailed Description
World class
Constructor & Destructor Documentation
◆ World()
World::World | ( | const std::string & | name = "MyWorld" , |
double | ppm = DEFAULT_PPM |
||
) |
◆ ~World()
|
virtual |
Member Function Documentation
◆ AddModel()
|
virtual |
◆ AddModelName()
void World::AddModelName | ( | Model * | mod, |
const std::string & | name | ||
) |
◆ AddPowerPack()
void World::AddPowerPack | ( | PowerPack * | pp | ) |
◆ AddSuperRegion()
SuperRegion * World::AddSuperRegion | ( | const point_int_t & | coord | ) |
◆ AddUpdateCallback()
void World::AddUpdateCallback | ( | world_callback_t | cb, |
void * | user | ||
) |
Attach a callback function, to be called with the argument at the end of a complete update step
◆ CallUpdateCallbacks()
|
protected |
Call all calbacks in cb_list, removing any that return true;.
◆ CancelQuit()
|
inline |
Cancel a local quit request.
◆ CancelQuitAll()
|
inline |
Cancel a global quit request.
◆ ClearRays()
void World::ClearRays | ( | ) |
◆ ClockString()
|
virtual |
Get human readable string that describes the current simulation time.
Reimplemented in Stg::WorldGui.
◆ ConsumeQueue()
void World::ConsumeQueue | ( | unsigned int | queue_num | ) |
consume events from the queue up to and including the current sim_time
◆ CreateModel()
◆ CreateSuperRegion()
SuperRegion * World::CreateSuperRegion | ( | point_int_t | origin | ) |
◆ DestroySuperRegion()
void World::DestroySuperRegion | ( | SuperRegion * | sr | ) |
◆ DisableEnergy()
|
inline |
◆ EnableEnergy()
|
inline |
◆ Enqueue()
|
inline |
Create a new simulation event to be handled in the future.
- Parameters
-
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.
◆ Extend()
|
inline |
Enlarge the bounding volume to include this point
◆ GetAllModels()
|
inline |
Returns a const reference to the set of models in the world.
◆ GetEventQueue()
unsigned int World::GetEventQueue | ( | Model * | mod | ) | const |
returns an event queue index number for a model to use for updates
◆ GetExtent()
|
inline |
Return the 3D bounding box of the world, in meters
◆ GetGround()
|
inline |
Return the floor model
◆ GetModel()
Model * World::GetModel | ( | const std::string & | name | ) | const |
Returns a pointer to the model identified by name, or NULL if nonexistent
◆ GetSuperRegion()
|
inline |
◆ GetSuperRegionCreate()
|
inline |
◆ GetUpdateCount()
|
inline |
Return the number of times the world has been updated.
◆ GetWorldFile()
|
inline |
Returns a pointer to the currently-open worlddfile object, or NULL if there is none.
◆ IsGUI()
|
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.
◆ Load() [1/2]
|
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().
- Returns
- true if load was successful, false otherwise
Reimplemented in Stg::WorldGui.
◆ Load() [2/2]
|
virtual |
Read the world content from the given stream, create a Worldfile object and configure the world from the contents, creating models as necessary. The created object persists, and can be retrieved later with World::GetWorldFile(). world_content can be any valid std::istream
object. If it's a file (std::ifstream
), worldfile_path
can be specified to be able to resolve relative includes. If worldfile_path
is empty, relative includes are not supported (if they are encountered, loading will fail), although includes (and even paths in general, e. g., for "bitmap") with a absolute path are supported.
- Returns
- true if load was successful, false otherwise
Reimplemented in Stg::WorldGui.
◆ LoadBlock()
void World::LoadBlock | ( | Worldfile * | wf, |
int | entity | ||
) |
◆ LoadBlockGroup()
void Stg::World::LoadBlockGroup | ( | Worldfile * | wf, |
int | entity | ||
) |
◆ LoadModel()
void World::LoadModel | ( | Worldfile * | wf, |
int | entity | ||
) |
◆ LoadSensor()
void World::LoadSensor | ( | Worldfile * | wf, |
int | entity | ||
) |
◆ Log()
◆ MapPoly()
void World::MapPoly | ( | const std::vector< point_int_t > & | poly, |
Block * | block, | ||
unsigned int | layer | ||
) |
Add the block to every raytrace bitmap cell that intersects the edges of the polygon.
◆ MetersToPixels() [1/2]
|
inline |
Return the bitmap coordinates corresponding to the location in meters.
◆ MetersToPixels() [2/2]
|
inline |
convert a distance in meters to a distance in world occupancy grid pixels
◆ NeedRedraw()
|
inline |
hint that the world needs to be redrawn if a GUI is attached
◆ PastQuitTime()
bool World::PastQuitTime | ( | ) |
Returns true iff the current time is greater than the time we should quit
◆ Paused()
|
inline |
◆ PopColor()
|
inlinevirtual |
Reimplemented in Stg::WorldGui.
◆ PushColor() [1/2]
|
inlinevirtual |
dummy implementations to be overloaded by GUI subclasses
Reimplemented in Stg::WorldGui.
◆ PushColor() [2/2]
|
inlinevirtual |
Reimplemented in Stg::WorldGui.
◆ Quit()
|
inline |
Request the world quits simulation before the next timestep.
◆ QuitAll()
|
inline |
Requests all worlds quit simulation before the next timestep.
◆ Raytrace() [1/3]
void World::Raytrace | ( | const Pose & | gpose, |
const meters_t | range, | ||
const radians_t | fov, | ||
const ray_test_func_t | func, | ||
const Model * | model, | ||
const void * | arg, | ||
const bool | ztest, | ||
std::vector< RaytraceResult > & | results | ||
) |
◆ Raytrace() [2/3]
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 | ||
) |
◆ Raytrace() [3/3]
RaytraceResult World::Raytrace | ( | const Ray & | ray | ) |
trace a ray.
◆ RecentlySelectedModel()
|
inlinevirtual |
Reimplemented in Stg::WorldGui.
◆ RecordRay()
void World::RecordRay | ( | double | x1, |
double | y1, | ||
double | x2, | ||
double | y2 | ||
) |
store rays traced for debugging purposes
◆ Redraw()
|
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.
◆ RegisterOption()
◆ Reload()
|
virtual |
◆ RemoveModel()
|
virtual |
◆ RemovePowerPack()
void World::RemovePowerPack | ( | PowerPack * | pp | ) |
◆ RemoveUpdateCallback()
int World::RemoveUpdateCallback | ( | world_callback_t | cb, |
void * | user | ||
) |
Remove a callback function. Any argument data passed to AddUpdateCallback is not automatically freed.
◆ Resolution()
|
inline |
Get the resolution in pixels-per-metre of the underlying discrete raytracing model
◆ Run()
|
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.
◆ Save()
|
virtual |
Save the current world state into a worldfile with the given filename.
- Parameters
-
Filename to save as.
Reimplemented in Stg::WorldGui.
◆ ShowClock()
|
inline |
Control printing time to stdout.
◆ SimTimeNow()
|
inline |
Returns the current simulated time in this world, in microseconds.
◆ Start()
|
inlinevirtual |
Reimplemented in Stg::WorldGui.
◆ Stop()
|
inlinevirtual |
Reimplemented in Stg::WorldGui.
◆ TestQuit()
|
inline |
◆ TogglePause()
|
inlinevirtual |
◆ TryCharge()
◆ UnLoad()
|
virtual |
Reimplemented in Stg::WorldGui.
◆ Update()
|
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.
◆ update_thread_entry()
|
static |
◆ UpdateAll()
|
static |
returns true when time to quit, false otherwise
◆ UpdateCount()
|
inline |
Member Data Documentation
◆ active_energy
std::set<Model *> Stg::World::active_energy |
Set of models that require energy calculations at each World::Update().
◆ active_velocity
std::set<ModelPosition *> Stg::World::active_velocity |
Set of models that require their positions to be recalculated at each World::Update().
◆ args
|
static |
contains the command line arguments passed to Stg::Init(), so that controllers can read them.
◆ cb_list
|
protected |
List of callback functions and arguments.
◆ ctrlargs
|
static |
◆ DEFAULT_PPM
|
static |
◆ event_queues
std::vector<std::priority_queue<Event> > Stg::World::event_queues |
Queue of pending simulation events for the main thread to handle.
◆ extent
|
protected |
Describes the 3D volume of the world.
◆ graphics
|
protected |
true iff we have a GUI
◆ ground
Model* Stg::World::ground |
Special model for the floor of the world
◆ option_table
|
protected |
GUI options (toggles) registered by models.
◆ paused
bool Stg::World::paused |
if true, the simulation is stopped
◆ pending_update_callbacks
std::vector<std::queue<Model *> > Stg::World::pending_update_callbacks |
Queue of pending simulation events for the main thread to handle.
◆ powerpack_list
|
protected |
List of all the powerpacks attached to models in the world.
◆ quit_time
|
protected |
World::quit is set true when this simulation time is reached
◆ ray_list
|
protected |
List of rays traced for debug visualization.
◆ rt_candidate_cells
std::vector<point_int_t> Stg::World::rt_candidate_cells |
◆ rt_cells
std::vector<point_int_t> Stg::World::rt_cells |
◆ sim_interval
◆ sim_time
|
protected |
the current sim time in this world in microseconds
◆ superregions
|
protected |
◆ update_cb_count
int Stg::World::update_cb_count |
debug instrumentation - making sure the number of update callbacks in each thread is consistent with the number that have been registered globally
◆ updates
|
protected |
the number of simulated time steps executed so far
◆ wf
|
protected |
If set, points to the worldfile used to create this world.
The documentation for this class was generated from the following files:
Generated on Sat Jan 21 2023 00:00:00 for Stage by