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

ModelPosition class More...

#include <stage.hh>

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

Classes

class  PoseVis
 
class  Waypoint
 
class  WaypointVis
 

Public Types

enum  ControlMode { CONTROL_ACCELERATION, CONTROL_VELOCITY, CONTROL_POSITION }
 
enum  DriveMode { DRIVE_DIFFERENTIAL, DRIVE_OMNI, DRIVE_CAR }
 
enum  LocalizationMode { LOCALIZATION_GPS, LOCALIZATION_ODOM }
 
- Public Types inherited from Stg::Model
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

Velocity GetGlobalVelocity () const
 
Velocity GetOdomError () const
 
Velocity GetVelocity () const
 
void GoTo (double x, double y, double a)
 
void GoTo (Pose pose)
 
 ModelPosition (World *world, Model *parent, const std::string &type)
 Constructor. More...
 
void SetAcceleration (double x, double y, double a)
 
void SetGlobalVelocity (const Velocity &gvel)
 
void SetOdom (Pose odom)
 
void SetSpeed (double x, double y, double a)
 
void SetSpeed (Velocity vel)
 
void SetTurnSpeed (double a)
 
void SetVelocity (const Velocity &val)
 
void SetXSpeed (double x)
 
void SetYSpeed (double y)
 
void SetZSpeed (double z)
 
void Stop ()
 
 ~ModelPosition ()
 Destructor. More...
 
- Public Member Functions inherited from Stg::Model
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)
 
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 ()
 

Public Attributes

Bounds acceleration_bounds [4]
 
Pose est_origin
 
Pose est_pose
 
Pose est_pose_error
 
Stg::ModelPosition::PoseVis posevis
 
Bounds velocity_bounds [4]
 
std::vector< Waypointwaypoints
 
Stg::ModelPosition::WaypointVis wpvis
 
- Public Attributes inherited from Stg::Model
class Stg::Model::Visibility vis
 

Protected Member Functions

virtual void Load ()
 
virtual void Move ()
 
virtual void Shutdown ()
 
virtual void Startup ()
 
virtual void Update ()
 
- Protected Member Functions inherited from Stg::Model
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)
 
ModelTestCollision ()
 
void UnMap (unsigned int layer)
 
void UnMap ()
 
void UnMapFromRoot (unsigned int layer)
 
void UnMapWithChildren (unsigned int layer)
 
virtual void UpdateCharge ()
 
void UpdateTrail ()
 
- Protected Member Functions inherited from Stg::Ancestor
AncestorLoad (Worldfile *wf, int section)
 
void Save (Worldfile *wf, int section)
 

Private Attributes

ControlMode control_mode
 
DriveMode drive_mode
 
Pose goal
 the current velocity or pose to reach, depending on the value of control_mode More...
 
Velocity integration_error
 errors to apply in simple odometry model More...
 
LocalizationMode localization_mode
 global or local mode More...
 
Velocity velocity
 
double wheelbase
 

Friends

class Canvas
 
class World
 

Additional Inherited Members

- Static Public Member Functions inherited from Stg::Model
static ModelLookupId (uint32_t id)
 
- Static Public Attributes inherited from Stg::Model
static std::map< std::string, creator_tname_map
 
- Static Protected Member Functions inherited from Stg::Model
static int UpdateWrapper (Model *mod, void *)
 
- Protected Attributes inherited from Stg::Model
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
 

Detailed Description

ModelPosition class

Definition at line 2777 of file stage.hh.

Member Enumeration Documentation

◆ ControlMode

Define a position control method

Enumerator
CONTROL_ACCELERATION 
CONTROL_VELOCITY 
CONTROL_POSITION 

Definition at line 2783 of file stage.hh.

◆ DriveMode

Define a driving method

Enumerator
DRIVE_DIFFERENTIAL 
DRIVE_OMNI 
DRIVE_CAR 

Definition at line 2789 of file stage.hh.

◆ LocalizationMode

Define a localization method

Enumerator
LOCALIZATION_GPS 
LOCALIZATION_ODOM 

Definition at line 2786 of file stage.hh.

Constructor & Destructor Documentation

◆ ModelPosition()

ModelPosition::ModelPosition ( World world,
Model parent,
const std::string &  type 
)

Constructor.

Definition at line 113 of file model_position.cc.

◆ ~ModelPosition()

ModelPosition::~ModelPosition ( void  )

Destructor.

Definition at line 152 of file model_position.cc.

Member Function Documentation

◆ GetGlobalVelocity()

Velocity ModelPosition::GetGlobalVelocity ( ) const

get the velocity of a model in the global CS

Definition at line 164 of file model_position.cc.

◆ GetOdomError()

Velocity Stg::ModelPosition::GetOdomError ( ) const
inline

Get (a copy of) the model's odometry integration error.

Definition at line 2822 of file stage.hh.

◆ GetVelocity()

Velocity Stg::ModelPosition::GetVelocity ( ) const
inline

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

Definition at line 2814 of file stage.hh.

◆ GoTo() [1/2]

void ModelPosition::GoTo ( double  x,
double  y,
double  a 
)

Sets the control mode to CONTROL_POSITION and sets the goal pose

Definition at line 637 of file model_position.cc.

◆ GoTo() [2/2]

void ModelPosition::GoTo ( Pose  pose)

Definition at line 646 of file model_position.cc.

◆ Load()

void ModelPosition::Load ( void  )
protectedvirtual

configure a model by reading from the current world file

Reimplemented from Stg::Model.

Definition at line 195 of file model_position.cc.

◆ Move()

void ModelPosition::Move ( void  )
protectedvirtual

Definition at line 526 of file model_position.cc.

◆ SetAcceleration()

void ModelPosition::SetAcceleration ( double  x,
double  y,
double  a 
)

Sets the control mode to CONTROL_ACCELERATION and sets the current accelerations to x, y (meters per second squared) and a (radians per second squared)

Definition at line 652 of file model_position.cc.

◆ SetGlobalVelocity()

void ModelPosition::SetGlobalVelocity ( const Velocity gvel)

set the velocity of a model in the global coordinate system

Definition at line 180 of file model_position.cc.

◆ SetOdom()

void ModelPosition::SetOdom ( Pose  odom)

Set the current pose estimate.

Set the current odometry estimate

Definition at line 664 of file model_position.cc.

◆ SetSpeed() [1/2]

void ModelPosition::SetSpeed ( double  x,
double  y,
double  a 
)

Sets the control_mode to CONTROL_VELOCITY and sets the goal velocity.

Definition at line 595 of file model_position.cc.

◆ SetSpeed() [2/2]

void ModelPosition::SetSpeed ( Velocity  vel)

Definition at line 628 of file model_position.cc.

◆ SetTurnSpeed()

void ModelPosition::SetTurnSpeed ( double  a)

Definition at line 622 of file model_position.cc.

◆ SetVelocity()

void ModelPosition::SetVelocity ( const Velocity val)

Definition at line 157 of file model_position.cc.

◆ SetXSpeed()

void ModelPosition::SetXSpeed ( double  x)

Definition at line 604 of file model_position.cc.

◆ SetYSpeed()

void ModelPosition::SetYSpeed ( double  y)

Definition at line 610 of file model_position.cc.

◆ SetZSpeed()

void ModelPosition::SetZSpeed ( double  z)

Definition at line 616 of file model_position.cc.

◆ Shutdown()

void ModelPosition::Shutdown ( void  )
protectedvirtual

Reimplemented from Stg::Model.

Definition at line 577 of file model_position.cc.

◆ Startup()

void ModelPosition::Startup ( void  )
protectedvirtual

Reimplemented from Stg::Model.

Definition at line 568 of file model_position.cc.

◆ Stop()

void ModelPosition::Stop ( )

Set velocity along all axes to to zero.

Definition at line 590 of file model_position.cc.

◆ Update()

void ModelPosition::Update ( void  )
protectedvirtual

Reimplemented from Stg::Model.

Definition at line 283 of file model_position.cc.

Friends And Related Function Documentation

◆ Canvas

friend class Canvas
friend

Definition at line 2778 of file stage.hh.

◆ World

friend class World
friend

Definition at line 2779 of file stage.hh.

Member Data Documentation

◆ acceleration_bounds

Bounds Stg::ModelPosition::acceleration_bounds[4]

Set the min and max acceleration in all 4 DOF

Definition at line 2802 of file stage.hh.

◆ control_mode

ControlMode Stg::ModelPosition::control_mode
private

Definition at line 2794 of file stage.hh.

◆ drive_mode

DriveMode Stg::ModelPosition::drive_mode
private

Definition at line 2795 of file stage.hh.

◆ est_origin

Pose Stg::ModelPosition::est_origin

Definition at line 2879 of file stage.hh.

◆ est_pose

Pose Stg::ModelPosition::est_pose

Definition at line 2877 of file stage.hh.

◆ est_pose_error

Pose Stg::ModelPosition::est_pose_error

Definition at line 2878 of file stage.hh.

◆ goal

Pose Stg::ModelPosition::goal
private

the current velocity or pose to reach, depending on the value of control_mode

Definition at line 2793 of file stage.hh.

◆ integration_error

Velocity Stg::ModelPosition::integration_error
private

errors to apply in simple odometry model

Definition at line 2797 of file stage.hh.

◆ localization_mode

LocalizationMode Stg::ModelPosition::localization_mode
private

global or local mode

Definition at line 2796 of file stage.hh.

◆ posevis

Stg::ModelPosition::PoseVis Stg::ModelPosition::posevis

◆ velocity

Velocity Stg::ModelPosition::velocity
private

Definition at line 2792 of file stage.hh.

◆ velocity_bounds

Bounds Stg::ModelPosition::velocity_bounds[4]

Set the min and max velocity in all 4 DOF

Definition at line 2805 of file stage.hh.

◆ waypoints

std::vector<Waypoint> Stg::ModelPosition::waypoints

Definition at line 2836 of file stage.hh.

◆ wheelbase

double Stg::ModelPosition::wheelbase
private

Definition at line 2798 of file stage.hh.

◆ wpvis

Stg::ModelPosition::WaypointVis Stg::ModelPosition::wpvis

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