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

#include <RTCBody.h>

Inheritance diagram for RTCBody:
Inheritance graph
[legend]

Public Member Functions

void createPorts (RTC::DataFlowComponentBase *comp)
 
void input ()
 
void output (OpenHRP::RobotState &state)
 
 RTCBody ()
 
 ~RTCBody ()
 
- Public Member Functions inherited from hrp::Body
void addSensor (Sensor *sensor, int sensorType, int id)
 
 Body ()
 
 Body (const Body &org)
 
void calcAngularMomentumJacobian (Link *base, dmatrix &H)
 
Vector3 calcCM ()
 
void calcCMJacobian (Link *base, dmatrix &J)
 
void calcForwardKinematics (bool calcVelocity=false, bool calcAcceleration=false)
 
void calcInverseDynamics (Link *link, Vector3 &out_f, Vector3 &out_tau)
 
void calcMassMatrix (dmatrix &out_M)
 
double calcTotalMass ()
 
void calcTotalMomentum (Vector3 &out_P, Vector3 &out_L)
 
void calcTotalMomentumFromJacobian (Vector3 &out_P, Vector3 &out_L)
 
void clearExternalForces ()
 
void clearSensorValues ()
 
LightcreateLight (Link *link, int lightType, const std::string &name)
 
SensorcreateSensor (Link *link, int sensorType, int id, const std::string &name)
 
void getDefaultRootPosition (Vector3 &out_p, Matrix33 &out_R)
 
JointPathPtr getJointPath (Link *baseLink, Link *targetLink)
 
void initializeConfiguration ()
 
bool installCustomizer ()
 
bool installCustomizer (BodyCustomizerInterface *customizerInterface)
 
bool isStaticModel ()
 
Linkjoint (int id) const
 
const std::vector< Link * > & joints () const
 
Lightlight (const std::string &name)
 
Linklink (int index) const
 
Linklink (const std::string &name) const
 
const LinkTraverselinks () const
 
const LinkTraverselinkTraverse () const
 
const std::string & modelName ()
 
const std::string & name ()
 
unsigned int numJoints () const
 
unsigned int numLinks () const
 
unsigned int numSensors (int sensorType) const
 
unsigned int numSensorTypes () const
 
void putInformation (std::ostream &out)
 
LinkrootLink () const
 
Sensorsensor (int sensorType, int sensorId) const
 
TSensor * sensor (const std::string &name) const
 
TSensor * sensor (int id) const
 
void setColumnOfMassMatrix (dmatrix &M, int column)
 
void setDefaultRootPosition (const Vector3 &p, const Matrix33 &R)
 
void setModelName (const std::string &name)
 
void setName (const std::string &name)
 
void setRootLink (Link *link)
 
void setVirtualJointForces ()
 
double totalMass () const
 
void updateLinkColdetModelPositions ()
 
void updateLinkTree ()
 
virtual ~Body ()
 
- Public Member Functions inherited from hrp::Referenced
 Referenced ()
 
virtual ~Referenced ()
 

Private Attributes

std::vector< RTC::TimedAcceleration3D > m_acc
 
std::vector< RTC::OutPort< RTC::TimedAcceleration3D > * > m_accOut
 
RTC::TimedDoubleSeq m_ddqCmd
 
RTC::InPort< RTC::TimedDoubleSeq > m_ddqCmdIn
 
RTC::TimedDoubleSeq m_dqCmd
 
RTC::InPort< RTC::TimedDoubleSeq > m_dqCmdIn
 
std::vector< RTC::TimedDoubleSeq > m_force
 
std::vector< RTC::OutPort< RTC::TimedDoubleSeq > * > m_forceOut
 
bool m_highgain
 
RTC::TimedPoint3D m_pos
 
RTC::OutPort< RTC::TimedPoint3D > m_posOut
 
RTC::TimedDoubleSeq m_q
 
RTC::TimedDoubleSeq m_qCmd
 
RTC::InPort< RTC::TimedDoubleSeq > m_qCmdIn
 
RTC::OutPort< RTC::TimedDoubleSeq > m_qOut
 
std::vector< RTC::TimedAngularVelocity3D > m_rate
 
std::vector< RTC::OutPort< RTC::TimedAngularVelocity3D > * > m_rateOut
 
RTC::TimedOrientation3D m_rpy
 
RTC::OutPort< RTC::TimedOrientation3D > m_rpyOut
 
RTC::TimedDoubleSeq m_tau
 
RTC::InPort< RTC::TimedDoubleSeq > m_tauIn
 

Additional Inherited Members

- Public Types inherited from hrp::Body
enum  ExtraJointType
 
- Static Public Member Functions inherited from hrp::Body
static BodyInterfacebodyInterface ()
 
- Public Attributes inherited from hrp::Body
 EJ_XY
 
 EJ_XYZ
 
 EJ_Z
 
std::vector< ExtraJointextraJoints
 
- Protected Member Functions inherited from hrp::Referenced
int refCounter ()
 

Detailed Description

Definition at line 14 of file RTCBody.h.

Constructor & Destructor Documentation

RTCBody::RTCBody ( )

Definition at line 7 of file RTCBody.cpp.

RTCBody::~RTCBody ( )

Definition at line 19 of file RTCBody.cpp.

Member Function Documentation

void RTCBody::createPorts ( RTC::DataFlowComponentBase comp)

Definition at line 23 of file RTCBody.cpp.

void RTCBody::input ( )

Definition at line 84 of file RTCBody.cpp.

void RTCBody::output ( OpenHRP::RobotState &  state)

Definition at line 135 of file RTCBody.cpp.

Member Data Documentation

std::vector<RTC::TimedAcceleration3D> RTCBody::m_acc
private

Definition at line 34 of file RTCBody.h.

std::vector<RTC::OutPort<RTC::TimedAcceleration3D> *> RTCBody::m_accOut
private

Definition at line 41 of file RTCBody.h.

RTC::TimedDoubleSeq RTCBody::m_ddqCmd
private

Definition at line 24 of file RTCBody.h.

RTC::InPort<RTC::TimedDoubleSeq> RTCBody::m_ddqCmdIn
private

Definition at line 29 of file RTCBody.h.

RTC::TimedDoubleSeq RTCBody::m_dqCmd
private

Definition at line 24 of file RTCBody.h.

RTC::InPort<RTC::TimedDoubleSeq> RTCBody::m_dqCmdIn
private

Definition at line 28 of file RTCBody.h.

std::vector<RTC::TimedDoubleSeq> RTCBody::m_force
private

Definition at line 36 of file RTCBody.h.

std::vector<RTC::OutPort<RTC::TimedDoubleSeq> *> RTCBody::m_forceOut
private

Definition at line 43 of file RTCBody.h.

bool RTCBody::m_highgain
private

Definition at line 45 of file RTCBody.h.

RTC::TimedPoint3D RTCBody::m_pos
private

Definition at line 31 of file RTCBody.h.

RTC::OutPort<RTC::TimedPoint3D> RTCBody::m_posOut
private

Definition at line 38 of file RTCBody.h.

RTC::TimedDoubleSeq RTCBody::m_q
private

Definition at line 33 of file RTCBody.h.

RTC::TimedDoubleSeq RTCBody::m_qCmd
private

Definition at line 24 of file RTCBody.h.

RTC::InPort<RTC::TimedDoubleSeq> RTCBody::m_qCmdIn
private

Definition at line 27 of file RTCBody.h.

RTC::OutPort<RTC::TimedDoubleSeq> RTCBody::m_qOut
private

Definition at line 40 of file RTCBody.h.

std::vector<RTC::TimedAngularVelocity3D> RTCBody::m_rate
private

Definition at line 35 of file RTCBody.h.

std::vector<RTC::OutPort<RTC::TimedAngularVelocity3D> *> RTCBody::m_rateOut
private

Definition at line 42 of file RTCBody.h.

RTC::TimedOrientation3D RTCBody::m_rpy
private

Definition at line 32 of file RTCBody.h.

RTC::OutPort<RTC::TimedOrientation3D> RTCBody::m_rpyOut
private

Definition at line 39 of file RTCBody.h.

RTC::TimedDoubleSeq RTCBody::m_tau
private

Definition at line 23 of file RTCBody.h.

RTC::InPort<RTC::TimedDoubleSeq> RTCBody::m_tauIn
private

Definition at line 26 of file RTCBody.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