Public Member Functions | Static Public Member Functions | Protected Attributes
GenericObjectContainer Class Reference

#include <GenericObjectContainer.h>

List of all members.

Public Member Functions

void actualizeForSceneContent ()
void endOfSimulation ()
 GenericObjectContainer ()
int getCount ()
boost::shared_ptr
< GenericObjectHandler
getFromAssociatedObject (int theAssociatedObjectID)
boost::shared_ptr
< GenericObjectHandler
getFromID (int theID)
boost::shared_ptr
< GenericObjectHandler
getFromIndex (int ind)
void handleSimulation ()
int insert (boost::shared_ptr< GenericObjectHandler > objectHandler)
void removeAll ()
void removeFromID (int theID)
void startOfSimulation ()
virtual ~GenericObjectContainer ()

Static Public Member Functions

static void simExtGetAllCustomData (SLuaCallBack *p)
static void simExtGetCustomDataFromHeader (SLuaCallBack *p)
static void simExtSetFloatArrayCustomDataFromHeader (SLuaCallBack *p)
static void simExtSetFloatCustomDataFromHeader (SLuaCallBack *p)
static void simExtSetIntCustomDataFromHeader (SLuaCallBack *p)

Protected Attributes

std::map< std::string,
boost::shared_ptr
< GenericObjectHandler > > 
_allExistingPlugins
std::vector< boost::shared_ptr
< GenericObjectHandler > > 
_allObjects
rosgraph_msgs::Clock _clock_msg
ros::NodeHandle _nh
pluginlib::ClassLoader
< GenericObjectHandler
_object_handler_loader
ros::Publisher _pubClock

Detailed Description

Definition at line 13 of file GenericObjectContainer.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 10 of file GenericObjectContainer.cpp.

Destroy the container after removing all objects inside.

Definition at line 33 of file GenericObjectContainer.cpp.


Member Function Documentation

This is called every time the scene content in V-REP might have changed (e.g. object added/removed/etc.). The method synchronizes the container with the current V-REP's scene content: we need to make sure that every object in V-REP's scene has exactly one element in this container.

Definition at line 115 of file GenericObjectContainer.cpp.

This is called at the end of simulation.

Definition at line 95 of file GenericObjectContainer.cpp.

Get the number of elements in the container.

Returns:
The number of elements in the container.

Definition at line 86 of file GenericObjectContainer.cpp.

boost::shared_ptr< GenericObjectHandler > GenericObjectContainer::getFromAssociatedObject ( int  theAssociatedObjectID)

Get the container of an object.

Parameters:
theAssociatedObjectIDThe unique ID of the object.
Returns:
The object element in the container.

Definition at line 77 of file GenericObjectContainer.cpp.

boost::shared_ptr< GenericObjectHandler > GenericObjectContainer::getFromID ( int  theID)

Returns the object corresponding to a given unique ID.

Parameters:
theIDThe unique ID of the object to be returned.
Returns:
A pointer to the object corresponding to the given ID or NULL if the object was not found.

Definition at line 62 of file GenericObjectContainer.cpp.

Returns the object correspImuonding to a container index.

Parameters:
indThe container index of the object to be returned.
Returns:
A pointer to the object corresponding to the given index or NULL if the object was not found.

Definition at line 71 of file GenericObjectContainer.cpp.

This is called at each simulation step, i.e. when the main script calls: simHandleModule.

Definition at line 106 of file GenericObjectContainer.cpp.

int GenericObjectContainer::insert ( boost::shared_ptr< GenericObjectHandler objectHandler)

Insert an object in the container.

Parameters:
objectHandlerA pointer to the object to be inserted.
Returns:
The ID of the inserted object.

Definition at line 53 of file GenericObjectContainer.cpp.

Remove all objects from the container.

Definition at line 37 of file GenericObjectContainer.cpp.

Remove the object corresponding to the given ID from the container.

Parameters:
theIDThe unique ID of the object to be removed.

Definition at line 42 of file GenericObjectContainer.cpp.

void GenericObjectContainer::simExtGetAllCustomData ( SLuaCallBack *  p) [static]

A Lua custom command that retrieves all custom data from an object and print it in the format described in CAccess class documentation.

Parameters:
pLua callback parameter. See V-REP main documentation for details.

Definition at line 209 of file GenericObjectContainer.cpp.

void GenericObjectContainer::simExtGetCustomDataFromHeader ( SLuaCallBack *  p) [static]

A Lua custom command that retrieves the custom data corresponding to a certain header (among those defined in CustomDataHeaders) from an object.

Parameters:
pLua callback parameter. See V-REP main documentation for details.

Definition at line 281 of file GenericObjectContainer.cpp.

A Lua custom command that sets the floating point vector custom data corresponding to a certain header (among those defined in CustomDataHeaders) from an object. TODO: use binding to pass the object container so that the object can be initialized each time the custom data are modified.

Parameters:
pLua callback parameter. See V-REP main documentation for details.

TODO: add output bool to indicate success

Definition at line 414 of file GenericObjectContainer.cpp.

simVoid GenericObjectContainer::simExtSetFloatCustomDataFromHeader ( SLuaCallBack *  p) [static]

A Lua custom command that sets the floating point custom data corresponding to a certain header (among those defined in CustomDataHeaders) from an object. TODO: use binding to pass the object container so that the object can be initialized each time the custom data are modified.

Parameters:
pLua callback parameter. See V-REP main documentation for details.

TODO: add output bool to indicate success

Definition at line 342 of file GenericObjectContainer.cpp.

simVoid GenericObjectContainer::simExtSetIntCustomDataFromHeader ( SLuaCallBack *  p) [static]

A Lua custom command that sets the integer point custom data corresponding to a certain header (among those defined in CustomDataHeaders) from an object. TODO: use binding to pass the object container so that the object can be initialized each time the custom data are modified.

Parameters:
pLua callback parameter. See V-REP main documentation for details.

TODO: add output bool to indicate success

Definition at line 488 of file GenericObjectContainer.cpp.

This is called at the start of simulation.

Definition at line 90 of file GenericObjectContainer.cpp.


Member Data Documentation

std::map<std::string, boost::shared_ptr<GenericObjectHandler> > GenericObjectContainer::_allExistingPlugins [protected]

Definition at line 132 of file GenericObjectContainer.h.

std::vector<boost::shared_ptr<GenericObjectHandler> > GenericObjectContainer::_allObjects [protected]

Definition at line 129 of file GenericObjectContainer.h.

rosgraph_msgs::Clock GenericObjectContainer::_clock_msg [protected]

Definition at line 136 of file GenericObjectContainer.h.

Definition at line 134 of file GenericObjectContainer.h.

Definition at line 131 of file GenericObjectContainer.h.

Definition at line 135 of file GenericObjectContainer.h.


The documentation for this class was generated from the following files:


vrep_ros_plugin
Author(s): Riccardo Spica , Giovanni Claudio
autogenerated on Sat Jun 8 2019 20:22:41