Public Member Functions | Public Attributes | Protected Attributes | Private Attributes | List of all members
Simulator Class Reference

sample RT component which has one data input port and one data output port More...

#include <Simulator.h>

Inheritance diagram for Simulator:
Inheritance graph
[legend]

Public Member Functions

void addCollisionCheckPair (BodyRTC *b1, BodyRTC *b2)
 
void appendLog ()
 
void checkCollision (OpenHRP::CollisionSequence &collisions)
 
void checkCollision ()
 
void clear ()
 
void init (Project &prj, BodyFactory &factory)
 
void init (Project &prj, GLscene *i_scene, RTC::CorbaNaming &naming)
 
void kinematicsOnly (bool flag)
 
virtual RTC::ReturnCode_t onActivated (RTC::UniqueId ec_id)
 
virtual RTC::ReturnCode_t onDeactivated (RTC::UniqueId ec_id)
 
bool oneStep ()
 
bool oneStep ()
 
virtual RTC::ReturnCode_t onExecute (RTC::UniqueId ec_id)
 
virtual RTC::ReturnCode_t onInitialize ()
 
void realTime (bool flag)
 
void setLogTimeStep (double time)
 
void setTotalTime (double time)
 
 Simulator (LogManager< SceneState > *i_log)
 
 Simulator (RTC::Manager *manager)
 Constructor. More...
 
double totalTime ()
 
virtual ~Simulator ()
 Destructor. More...
 
- Public Member Functions inherited from hrp::World< hrp::ConstraintForceSolver >
virtual void calcNextState (OpenHRP::CollisionSequence &corbaCollisionSequence)
 
virtual void initialize ()
 
 World ()
 
- Public Member Functions inherited from hrp::WorldBase
int addBody (BodyPtr body)
 
BodyPtr body (int index)
 
BodyPtr body (const std::string &name)
 
int bodyIndex (const std::string &name)
 
virtual void calcNextState ()
 
void clearBodies ()
 
void clearCollisionPairs ()
 
double currentTime (void) const
 
void enableSensors (bool on)
 
ForwardDynamicsPtr forwardDynamics (int index)
 
const Vector3getGravityAcceleration ()
 
std::pair< int, bool > getIndexOfLinkPairs (Link *link1, Link *link2)
 
unsigned int numBodies ()
 
void setCurrentTime (double tm)
 
void setEulerMethod ()
 
void setGravityAcceleration (const Vector3 &g)
 
void setRungeKuttaMethod ()
 
void setTimeStep (double dt)
 
double timeStep (void) const
 
 WorldBase ()
 
virtual ~WorldBase ()
 
- Public Member Functions inherited from ThreadedObject
bool isPausing ()
 
bool isRunning ()
 
void notifyFinish ()
 
void pause ()
 
void resume ()
 
void start ()
 
void stop ()
 
 ThreadedObject ()
 
void wait ()
 
 ~ThreadedObject ()
 
- Public Member Functions inherited from RTC::DataFlowComponentBase
 DataFlowComponentBase (Manager *manager)
 
void init ()
 
virtual ~DataFlowComponentBase (void)
 
- Public Member Functions inherited from RTC::RTObject_impl
ReturnCode_t activate (RTC::UniqueId ec_id)
 
void addConfigurationParamListener (ConfigurationParamListenerType type, ConfigurationParamListener *listener, bool autoclean=true)
 
ConfigurationParamListeneraddConfigurationParamListener (ConfigurationParamListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const char *, const char *))
 
void addConfigurationSetListener (ConfigurationSetListenerType type, ConfigurationSetListener *listener, bool autoclean=true)
 
ConfigurationSetListeneraddConfigurationSetListener (ConfigurationSetListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const coil::Properties &config_set))
 
void addConfigurationSetNameListener (ConfigurationSetNameListenerType type, ConfigurationSetNameListener *listener, bool autoclean=true)
 
ConfigurationSetNameListeneraddConfigurationSetNameListener (ConfigurationSetNameListenerType type, Listener &obj, void(Listener::*memfunc)(const char *))
 
void addExecutionContextActionListener (ECActionListenerType listener_type, ECActionListener *listener, bool autoclean=true)
 
ECActionListeneraddExecutionContextActionListener (ECActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(UniqueId))
 
bool addInPort (const char *name, InPortBase &inport)
 
bool addOutPort (const char *name, OutPortBase &outport)
 
bool addPort (PortBase &port)
 
bool addPort (PortService_ptr port)
 
bool addPort (CorbaPort &port)
 
PortActionListeneraddPortActionListener (PortActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const RTC::PortProfile &))
 
void addPortActionListener (PortActionListenerType listener_type, PortActionListener *listener, bool autoclean=true)
 
void addPortConnectListener (PortConnectListenerType listener_type, PortConnectListener *listener, bool autoclean=true)
 
PortConnectListeneraddPortConnectListener (PortConnectListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const char *, ConnectorProfile &))
 
void addPortConnectRetListener (PortConnectRetListenerType listener_type, PortConnectRetListener *listener, bool autoclean=true)
 
PortConnectRetListeneraddPortConnectRetListener (PortConnectRetListenerType listener_type, Listener &obj, void(Listener::*memfunc)(const char *, ConnectorProfile &, ReturnCode_t))
 
void addPostComponentActionListener (PostComponentActionListenerType listener_type, PostComponentActionListener *listener, bool autoclean=true)
 
PostComponentActionListeneraddPostComponentActionListener (PostCompActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(UniqueId ec_id, ReturnCode_t ret))
 
void addPreComponentActionListener (PreComponentActionListenerType listener_type, PreComponentActionListener *listener, bool autoclean=true)
 
PreComponentActionListeneraddPreComponentActionListener (PreCompActionListenerType listener_type, Listener &obj, void(Listener::*memfunc)(UniqueId ec_id))
 
bool addSdoServiceConsumer (const SDOPackage::ServiceProfile &prof)
 
bool addSdoServiceProvider (const SDOPackage::ServiceProfile &prof, SdoServiceProviderBase *provider)
 
UniqueId attach_context (ExecutionContext_ptr exec_context)
 
UniqueId bindContext (ExecutionContext_ptr exec_context)
 
bool bindParameter (const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo)
 
ReturnCode_t deactivate (RTC::UniqueId ec_id)
 
void deletePort (PortService_ptr port)
 
void deletePort (CorbaPort &port)
 
void deletePort (PortBase &port)
 
void deletePortByName (const char *port_name)
 
ReturnCode_t detach_context (UniqueId exec_handle)
 
virtual ReturnCode_t exit ()
 
virtual ReturnCode_t finalize ()
 
void finalizeContexts ()
 
void finalizePorts ()
 
virtual ComponentProfile * get_component_profile ()
 
virtual SDOPackage::Configuration_ptr get_configuration ()
 
virtual ExecutionContext_ptr get_context (UniqueId exec_handle)
 
virtual ExecutionContextHandle_t get_context_handle (ExecutionContext_ptr cxt)
 
virtual SDOPackage::DeviceProfile * get_device_profile ()
 
virtual SDOPackage::Monitoring_ptr get_monitoring ()
 
virtual SDOPackage::OrganizationList * get_organizations ()
 
virtual ExecutionContextListget_owned_contexts ()
 
virtual SDOPackage::OrganizationList * get_owned_organizations ()
 
virtual ExecutionContextListget_participating_contexts ()
 
virtual PortServiceListget_ports ()
 
virtual char * get_sdo_id ()
 
virtual SDOPackage::SDOService_ptr get_sdo_service (const char *id)
 
virtual char * get_sdo_type ()
 
virtual SDOPackage::ServiceProfile * get_service_profile (const char *id)
 
virtual SDOPackage::ServiceProfileList * get_service_profiles ()
 
virtual CORBA::Any * get_status (const char *name)
 
virtual SDOPackage::NVListget_status_list ()
 
const char * getCategory ()
 
const char * getDescription ()
 
ExecutionContext_ptr getExecutionContext (RTC::UniqueId ec_id)
 
double getExecutionRate (RTC::UniqueId ec_id)
 
const char * getInstanceName ()
 
std::vector< std::string > getNamingNames ()
 
RTObject_ptr getObjRef () const
 
coil::PropertiesgetProperties ()
 
const char * getTypeName ()
 
const char * getVendor ()
 
const char * getVersion ()
 
virtual ReturnCode_t initialize ()
 
virtual CORBA::Boolean is_alive (ExecutionContext_ptr exec_context)
 
bool isOwnExecutionContext (RTC::UniqueId ec_id)
 
virtual ReturnCode_t on_aborting (UniqueId exec_handle)
 
virtual ReturnCode_t on_activated (UniqueId exec_handle)
 
virtual ReturnCode_t on_deactivated (UniqueId exec_handle)
 
virtual ReturnCode_t on_error (UniqueId exec_handle)
 
virtual ReturnCode_t on_execute (UniqueId exec_handle)
 
virtual ReturnCode_t on_finalize ()
 
virtual ReturnCode_t on_initialize ()
 
virtual ReturnCode_t on_rate_changed (UniqueId exec_handle)
 
virtual ReturnCode_t on_reset (UniqueId exec_handle)
 
virtual ReturnCode_t on_shutdown (UniqueId exec_handle)
 
virtual ReturnCode_t on_startup (UniqueId exec_handle)
 
virtual ReturnCode_t on_state_update (UniqueId exec_handle)
 
bool readAll ()
 
void registerInPort (const char *name, InPortBase &inport)
 
void registerOutPort (const char *name, OutPortBase &outport)
 
void registerPort (PortBase &port)
 
void registerPort (PortService_ptr port)
 
void registerPort (CorbaPort &port)
 
void removeConfigurationParamListener (ConfigurationParamListenerType type, ConfigurationParamListener *listener)
 
void removeConfigurationSetListener (ConfigurationSetListenerType type, ConfigurationSetListener *listener)
 
void removeConfigurationSetNameListener (ConfigurationSetNameListenerType type, ConfigurationSetNameListener *listener)
 
void removeExecutionContextActionListener (ECActionListenerType listener_type, ECActionListener *listener)
 
bool removeInPort (InPortBase &port)
 
bool removeOutPort (OutPortBase &port)
 
bool removePort (PortService_ptr port)
 
bool removePort (CorbaPort &port)
 
bool removePort (PortBase &port)
 
void removePortActionListener (PortActionListenerType listener_type, PortActionListener *listener)
 
void removePortConnectListener (PortConnectListenerType listener_type, PortConnectListener *listener)
 
void removePortConnectRetListener (PortConnectRetListenerType listener_type, PortConnectRetListener *listener)
 
void removePostComponentActionListener (PostComponentActionListenerType listener_type, PostComponentActionListener *listener)
 
void removePreComponentActionListener (PreComponentActionListenerType listener_type, PreComponentActionListener *listener)
 
bool removeSdoServiceConsumer (const char *id)
 
bool removeSdoServiceProvider (const char *id)
 
ReturnCode_t reset (RTC::UniqueId ec_id)
 
 RTObject_impl (CORBA::ORB_ptr orb, PortableServer::POA_ptr poa)
 
 RTObject_impl (Manager *manager)
 
ReturnCode_t setExecutionRate (RTC::UniqueId ec_id, double rate)
 
void setInstanceName (const char *instance_name)
 
void setObjRef (const RTObject_ptr rtobj)
 
void setProperties (const coil::Properties &prop)
 
void setReadAll (bool read=true, bool completion=false)
 
void setWriteAll (bool write=true, bool completion=false)
 
void updateParameters (const char *config_set)
 
bool writeAll ()
 
virtual ~RTObject_impl (void)
 

Public Attributes

std::vector< BodyRTCPtrbodies
 
GLscenescene
 
OpenHRP::WorldState state
 
double totalTime
 
hrp::World< hrp::ConstraintForceSolverworld
 
- Public Attributes inherited from hrp::World< hrp::ConstraintForceSolver >
hrp::ConstraintForceSolver constraintForceSolver
 

Protected Attributes

OpenHRP::SceneState m_sceneState
 
OutPort< OpenHRP::SceneState > m_sceneStateOut
 
- Protected Attributes inherited from hrp::WorldBase
std::vector< BodyInfo > bodyInfoArray
 
double currentTime_
 
bool sensorsAreEnabled
 
double timeStep_
 
- Protected Attributes inherited from RTC::RTObject_impl
ComponentActionListeners m_actionListeners
 
ConfigAdmin m_configsets
 
bool m_created
 
std::vector< ExecutionContextBase * > m_eclist
 
ExecutionContextServiceList m_ecMine
 
ExecutionContextServiceList m_ecOther
 
bool m_exiting
 
std::vector< InPortBase * > m_inports
 
RTObject_var m_objref
 
std::vector< OutPortBase * > m_outports
 
Managerm_pManager
 
CORBA::ORB_var m_pORB
 
PortAdmin m_portAdmin
 
PortConnectListeners m_portconnListeners
 
PortableServer::POA_var m_pPOA
 
ComponentProfile m_profile
 
coil::Properties m_properties
 
SDOPackage::Configuration_var m_pSdoConfig
 
SDOPackage::Configuration_implm_pSdoConfigImpl
 
bool m_readAll
 
bool m_readAllCompletion
 
SDOPackage::OrganizationList m_sdoOrganizations
 
SDOPackage::OrganizationList m_sdoOwnedOrganizations
 
SdoServiceAdmin m_sdoservice
 
SDOPackage::NVList m_sdoStatus
 
bool m_writeAll
 
bool m_writeAllCompletion
 
Logger rtclog
 

Private Attributes

bool adjustTime
 
struct timeval beginTime
 
OpenHRP::CollisionSequence collisions
 
int dummy
 
LogManager< SceneState > * log
 
std::vector< RTCBodyPtrm_bodies
 
bool m_kinematicsOnly
 
double m_logTimeStep
 
double m_nextLogTime
 
OpenHRP::OnlineViewer_var m_olv
 
std::string m_project
 
OpenHRP::WorldState m_state
 
double m_totalTime
 
bool m_useOLV
 
hrp::World< hrp::ConstraintForceSolverm_world
 
std::vector< hrp::ColdetLinkPairPtrpairs
 
std::vector< ClockReceiverreceivers
 
std::deque< struct timeval > startTimes
 
SceneState state
 
TimeMeasure tm_collision
 
TimeMeasure tm_control
 
TimeMeasure tm_dynamics
 

Additional Inherited Members

- Public Types inherited from RTC::RTObject_impl
typedef ExecutionContextActionListener ECActionListener
 
typedef ExecutionContextActionListenerType ECActionListenerType
 
typedef PostComponentActionListener PostCompActionListener
 
typedef PostComponentActionListenerType PostCompActionListenerType
 
typedef PreComponentActionListener PreCompActionListener
 
typedef PreComponentActionListenerType PreCompActionListenerType
 
- Protected Member Functions inherited from RTC::RTObject_impl
virtual ReturnCode_t onAborting (RTC::UniqueId exec_handle)
 
void onAddPort (const PortProfile &pprof)
 
void onAttachExecutionContext (UniqueId ec_id)
 
void onDetachExecutionContext (UniqueId ec_id)
 
virtual ReturnCode_t onError (RTC::UniqueId exec_handle)
 
virtual ReturnCode_t onFinalize ()
 
virtual ReturnCode_t onRateChanged (RTC::UniqueId exec_handle)
 
void onRemovePort (const PortProfile &pprof)
 
virtual ReturnCode_t onReset (RTC::UniqueId exec_handle)
 
virtual ReturnCode_t onShutdown (RTC::UniqueId exec_handle)
 
virtual ReturnCode_t onStartup (RTC::UniqueId exec_handle)
 
virtual ReturnCode_t onStateUpdate (RTC::UniqueId exec_handle)
 
void postOnAborting (UniqueId ec_id, ReturnCode_t ret)
 
void postOnActivated (UniqueId ec_id, ReturnCode_t ret)
 
void postOnDeactivated (UniqueId ec_id, ReturnCode_t ret)
 
void postOnError (UniqueId ec_id, ReturnCode_t ret)
 
void postOnExecute (UniqueId ec_id, ReturnCode_t ret)
 
void postOnFinalize (UniqueId ec_id, ReturnCode_t ret)
 
void postOnInitialize (UniqueId ec_id, ReturnCode_t ret)
 
void postOnRateChanged (UniqueId ec_id, ReturnCode_t ret)
 
void postOnReset (UniqueId ec_id, ReturnCode_t ret)
 
void postOnShutdown (UniqueId ec_id, ReturnCode_t ret)
 
void postOnStartup (UniqueId ec_id, ReturnCode_t ret)
 
void postOnStateUpdate (UniqueId ec_id, ReturnCode_t ret)
 
void preOnAborting (UniqueId ec_id)
 
void preOnActivated (UniqueId ec_id)
 
void preOnDeactivated (UniqueId ec_id)
 
void preOnError (UniqueId ec_id)
 
void preOnExecute (UniqueId ec_id)
 
void preOnFinalize (UniqueId ec_id)
 
void preOnInitialize (UniqueId ec_id)
 
void preOnRateChanged (UniqueId ec_id)
 
void preOnReset (UniqueId ec_id)
 
void preOnShutdown (UniqueId ec_id)
 
void preOnStartup (UniqueId ec_id)
 
void preOnStateUpdate (UniqueId ec_id)
 
void shutdown ()
 

Detailed Description

sample RT component which has one data input port and one data output port

Definition at line 43 of file rtc/Simulator/Simulator.h.

Constructor & Destructor Documentation

Simulator::Simulator ( RTC::Manager manager)

Constructor.

Parameters
managerpointer to the Manager

Definition at line 41 of file rtc/Simulator/Simulator.cpp.

Simulator::~Simulator ( )
virtual

Destructor.

Definition at line 50 of file rtc/Simulator/Simulator.cpp.

Simulator::Simulator ( LogManager< SceneState > *  i_log)

Definition at line 4 of file util/simulator/Simulator.cpp.

Member Function Documentation

void Simulator::addCollisionCheckPair ( BodyRTC b1,
BodyRTC b2 
)

Definition at line 203 of file util/simulator/Simulator.cpp.

void Simulator::appendLog ( )

Definition at line 34 of file util/simulator/Simulator.cpp.

void Simulator::checkCollision ( OpenHRP::CollisionSequence &  collisions)

Definition at line 48 of file util/simulator/Simulator.cpp.

void Simulator::checkCollision ( )

Definition at line 43 of file util/simulator/Simulator.cpp.

void Simulator::clear ( void  )

Definition at line 188 of file util/simulator/Simulator.cpp.

void Simulator::init ( Project prj,
BodyFactory factory 
)

Definition at line 9 of file util/simulator/Simulator.cpp.

void Simulator::init ( Project prj,
GLscene i_scene,
RTC::CorbaNaming naming 
)
inline

Definition at line 38 of file SimulatorUtil.h.

void Simulator::kinematicsOnly ( bool  flag)

Definition at line 245 of file util/simulator/Simulator.cpp.

RTC::ReturnCode_t Simulator::onActivated ( RTC::UniqueId  ec_id)
virtual

Reimplemented from RTC::RTObject_impl.

Definition at line 110 of file rtc/Simulator/Simulator.cpp.

RTC::ReturnCode_t Simulator::onDeactivated ( RTC::UniqueId  ec_id)
virtual

Reimplemented from RTC::RTObject_impl.

Definition at line 261 of file rtc/Simulator/Simulator.cpp.

bool Simulator::oneStep ( )
virtual

Reimplemented from ThreadedObject.

Definition at line 90 of file util/simulator/Simulator.cpp.

bool Simulator::oneStep ( )
inlinevirtual

Reimplemented from ThreadedObject.

Definition at line 48 of file SimulatorUtil.h.

RTC::ReturnCode_t Simulator::onExecute ( RTC::UniqueId  ec_id)
virtual

Reimplemented from RTC::RTObject_impl.

Definition at line 267 of file rtc/Simulator/Simulator.cpp.

RTC::ReturnCode_t Simulator::onInitialize ( void  )
virtual

Reimplemented from RTC::RTObject_impl.

Definition at line 56 of file rtc/Simulator/Simulator.cpp.

void Simulator::realTime ( bool  flag)
inline

Definition at line 23 of file util/simulator/Simulator.h.

void Simulator::setLogTimeStep ( double  time)
inline

Definition at line 26 of file util/simulator/Simulator.h.

void Simulator::setTotalTime ( double  time)
inline

Definition at line 24 of file util/simulator/Simulator.h.

double Simulator::totalTime ( )
inline

Definition at line 25 of file util/simulator/Simulator.h.

Member Data Documentation

bool Simulator::adjustTime
private

Definition at line 39 of file util/simulator/Simulator.h.

struct timeval Simulator::beginTime
private

Definition at line 41 of file util/simulator/Simulator.h.

std::vector<BodyRTCPtr> Simulator::bodies

Definition at line 85 of file SimulatorUtil.h.

OpenHRP::CollisionSequence Simulator::collisions
private

Definition at line 35 of file util/simulator/Simulator.h.

int Simulator::dummy
private

Definition at line 147 of file rtc/Simulator/Simulator.h.

LogManager<SceneState>* Simulator::log
private

Definition at line 32 of file util/simulator/Simulator.h.

std::vector<RTCBodyPtr> Simulator::m_bodies
private

Definition at line 141 of file rtc/Simulator/Simulator.h.

bool Simulator::m_kinematicsOnly
private

Definition at line 143 of file rtc/Simulator/Simulator.h.

double Simulator::m_logTimeStep
private

Definition at line 37 of file util/simulator/Simulator.h.

double Simulator::m_nextLogTime
private

Definition at line 37 of file util/simulator/Simulator.h.

OpenHRP::OnlineViewer_var Simulator::m_olv
private

Definition at line 145 of file rtc/Simulator/Simulator.h.

std::string Simulator::m_project
private

Definition at line 142 of file rtc/Simulator/Simulator.h.

OpenHRP::SceneState Simulator::m_sceneState
protected

Definition at line 119 of file rtc/Simulator/Simulator.h.

OutPort<OpenHRP::SceneState> Simulator::m_sceneStateOut
protected

Definition at line 120 of file rtc/Simulator/Simulator.h.

OpenHRP::WorldState Simulator::m_state
private

Definition at line 146 of file rtc/Simulator/Simulator.h.

double Simulator::m_totalTime
private

Definition at line 37 of file util/simulator/Simulator.h.

bool Simulator::m_useOLV
private

Definition at line 144 of file rtc/Simulator/Simulator.h.

hrp::World<hrp::ConstraintForceSolver> Simulator::m_world
private

Definition at line 140 of file rtc/Simulator/Simulator.h.

std::vector<hrp::ColdetLinkPairPtr> Simulator::pairs
private

Definition at line 34 of file util/simulator/Simulator.h.

std::vector< ClockReceiver > Simulator::receivers
private

Definition at line 33 of file util/simulator/Simulator.h.

GLscene* Simulator::scene

Definition at line 89 of file SimulatorUtil.h.

std::deque<struct timeval> Simulator::startTimes
private

Definition at line 40 of file util/simulator/Simulator.h.

SceneState Simulator::state
private

Definition at line 36 of file util/simulator/Simulator.h.

OpenHRP::WorldState Simulator::state

Definition at line 87 of file SimulatorUtil.h.

TimeMeasure Simulator::tm_collision
private

Definition at line 38 of file util/simulator/Simulator.h.

TimeMeasure Simulator::tm_control
private

Definition at line 38 of file util/simulator/Simulator.h.

TimeMeasure Simulator::tm_dynamics
private

Definition at line 38 of file util/simulator/Simulator.h.

double Simulator::totalTime

Definition at line 88 of file SimulatorUtil.h.

Definition at line 84 of file SimulatorUtil.h.


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


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Thu May 6 2021 02:41:53