Public Member Functions | Public Attributes | Protected Attributes | Private Attributes
SequencePlayer Class Reference

#include <SequencePlayer.h>

Inheritance diagram for SequencePlayer:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool addJointGroup (const char *gname, const OpenHRP::SequencePlayerService::StrSequence &jnames)
bool clearJointAngles ()
bool clearJointAnglesOfGroup (const char *gname)
void loadPattern (const char *basename, double time)
virtual RTC::ReturnCode_t onActivated (RTC::UniqueId ec_id)
virtual RTC::ReturnCode_t onExecute (RTC::UniqueId ec_id)
virtual RTC::ReturnCode_t onFinalize ()
virtual RTC::ReturnCode_t onInitialize ()
seqplayplayer ()
void playPattern (const OpenHRP::dSequenceSequence &pos, const OpenHRP::dSequenceSequence &rpy, const OpenHRP::dSequenceSequence &zmp, const OpenHRP::dSequence &tm)
bool playPatternOfGroup (const char *gname, const OpenHRP::dSequenceSequence &pos, const OpenHRP::dSequence &tm)
bool removeJointGroup (const char *gname)
hrp::BodyPtr robot ()
 SequencePlayer (RTC::Manager *manager)
bool setBasePos (const double *pos, double tm)
bool setBaseRpy (const double *rpy, double tm)
void setClearFlag ()
bool setInitialState (double tm=0.0)
bool setInterpolationMode (OpenHRP::SequencePlayerService::interpolationMode i_mode_)
bool setJointAngle (short id, double angle, double tm)
bool setJointAngles (const double *angles, double tm)
bool setJointAngles (const double *angles, const bool *mask, double tm)
bool setJointAnglesOfGroup (const char *gname, const OpenHRP::dSequence &jvs, double tm)
bool setJointAnglesSequence (const OpenHRP::dSequenceSequence angless, const OpenHRP::bSequence &mask, const OpenHRP::dSequence &times)
bool setJointAnglesSequenceFull (const OpenHRP::dSequenceSequence i_jvss, const OpenHRP::dSequenceSequence i_vels, const OpenHRP::dSequenceSequence i_torques, const OpenHRP::dSequenceSequence i_poss, const OpenHRP::dSequenceSequence i_rpys, const OpenHRP::dSequenceSequence i_accs, const OpenHRP::dSequenceSequence i_zmps, const OpenHRP::dSequenceSequence i_wrenches, const OpenHRP::dSequenceSequence i_optionals, const dSequence i_tms)
bool setJointAnglesSequenceOfGroup (const char *gname, const OpenHRP::dSequenceSequence angless, const OpenHRP::dSequence &times)
void setMaxIKError (double pos, double rot)
void setMaxIKIteration (short iter)
bool setTargetPose (const char *gname, const double *xyz, const double *rpy, double tm, const char *frame_name)
bool setWrenches (const double *wrenches, double tm)
bool setZmp (const double *zmp, double tm)
void waitInterpolation ()
bool waitInterpolationOfGroup (const char *gname)
virtual ~SequencePlayer ()

Public Attributes

double dt

Protected Attributes

TimedAcceleration3D m_accRef
OutPort< TimedAcceleration3D > m_accRefOut
TimedPoint3D m_basePos
TimedPoint3D m_basePosInit
InPort< TimedPoint3D > m_basePosInitIn
OutPort< TimedPoint3D > m_basePosOut
TimedOrientation3D m_baseRpy
TimedOrientation3D m_baseRpyInit
InPort< TimedOrientation3D > m_baseRpyInitIn
OutPort< TimedOrientation3D > m_baseRpyOut
TimedDoubleSeq m_optionalData
OutPort< TimedDoubleSeq > m_optionalDataOut
TimedDoubleSeq m_qInit
InPort< TimedDoubleSeq > m_qInitIn
TimedDoubleSeq m_qRef
OutPort< TimedDoubleSeq > m_qRefOut
RTC::CorbaPort m_SequencePlayerServicePort
SequencePlayerService_impl m_service0
TimedDoubleSeq m_tqRef
OutPort< TimedDoubleSeq > m_tqRefOut
std::vector< TimedDoubleSeq > m_wrenches
std::vector< OutPort
< TimedDoubleSeq > * > 
m_wrenchesOut
TimedPoint3D m_zmpRef
TimedPoint3D m_zmpRefInit
InPort< TimedPoint3D > m_zmpRefInitIn
OutPort< TimedPoint3D > m_zmpRefOut

Private Attributes

int dummy
bool m_clearFlag
unsigned int m_debugLevel
double m_error_pos
double m_error_rot
std::string m_fixedLink
hrp::Vector3 m_fixedP
hrp::Matrix33 m_fixedR
std::string m_gname
short m_iteration
coil::Mutex m_mutex
hrp::Vector3 m_offsetP
hrp::Matrix33 m_offsetR
hrp::BodyPtr m_robot
seqplaym_seq
double m_timeToStartPlaying
bool m_waitFlag
sem_t m_waitSem
size_t optional_data_dim

Detailed Description

Definition at line 40 of file SequencePlayer.h.


Constructor & Destructor Documentation

Definition at line 43 of file SequencePlayer.cpp.

Definition at line 72 of file SequencePlayer.cpp.


Member Function Documentation

bool SequencePlayer::addJointGroup ( const char *  gname,
const OpenHRP::SequencePlayerService::StrSequence &  jnames 
)

Definition at line 823 of file SequencePlayer.cpp.

Definition at line 477 of file SequencePlayer.cpp.

Definition at line 506 of file SequencePlayer.cpp.

void SequencePlayer::loadPattern ( const char *  basename,
double  time 
)

Definition at line 701 of file SequencePlayer.cpp.

Reimplemented from RTC::RTObject_impl.

Definition at line 207 of file SequencePlayer.cpp.

Reimplemented from RTC::RTObject_impl.

Definition at line 221 of file SequencePlayer.cpp.

Reimplemented from RTC::RTObject_impl.

Definition at line 185 of file SequencePlayer.cpp.

Reimplemented from RTC::RTObject_impl.

Definition at line 77 of file SequencePlayer.cpp.

Definition at line 96 of file SequencePlayer.h.

void SequencePlayer::playPattern ( const OpenHRP::dSequenceSequence &  pos,
const OpenHRP::dSequenceSequence &  rpy,
const OpenHRP::dSequenceSequence &  zmp,
const OpenHRP::dSequence &  tm 
)

Definition at line 789 of file SequencePlayer.cpp.

bool SequencePlayer::playPatternOfGroup ( const char *  gname,
const OpenHRP::dSequenceSequence &  pos,
const OpenHRP::dSequence &  tm 
)

Definition at line 869 of file SequencePlayer.cpp.

bool SequencePlayer::removeJointGroup ( const char *  gname)

Definition at line 845 of file SequencePlayer.cpp.

Definition at line 97 of file SequencePlayer.h.

bool SequencePlayer::setBasePos ( const double *  pos,
double  tm 
)

Definition at line 544 of file SequencePlayer.cpp.

bool SequencePlayer::setBaseRpy ( const double *  rpy,
double  tm 
)

Definition at line 554 of file SequencePlayer.cpp.

Definition at line 358 of file SequencePlayer.cpp.

bool SequencePlayer::setInitialState ( double  tm = 0.0)

Definition at line 750 of file SequencePlayer.cpp.

bool SequencePlayer::setInterpolationMode ( OpenHRP::SequencePlayerService::interpolationMode  i_mode_)

Definition at line 806 of file SequencePlayer.cpp.

bool SequencePlayer::setJointAngle ( short  id,
double  angle,
double  tm 
)

Definition at line 387 of file SequencePlayer.cpp.

bool SequencePlayer::setJointAngles ( const double *  angles,
double  tm 
)

Definition at line 411 of file SequencePlayer.cpp.

bool SequencePlayer::setJointAngles ( const double *  angles,
const bool *  mask,
double  tm 
)

Definition at line 436 of file SequencePlayer.cpp.

bool SequencePlayer::setJointAnglesOfGroup ( const char *  gname,
const OpenHRP::dSequence &  jvs,
double  tm 
)

Definition at line 857 of file SequencePlayer.cpp.

bool SequencePlayer::setJointAnglesSequence ( const OpenHRP::dSequenceSequence  angless,
const OpenHRP::bSequence &  mask,
const OpenHRP::dSequence &  times 
)

Definition at line 454 of file SequencePlayer.cpp.

bool SequencePlayer::setJointAnglesSequenceFull ( const OpenHRP::dSequenceSequence  i_jvss,
const OpenHRP::dSequenceSequence  i_vels,
const OpenHRP::dSequenceSequence  i_torques,
const OpenHRP::dSequenceSequence  i_poss,
const OpenHRP::dSequenceSequence  i_rpys,
const OpenHRP::dSequenceSequence  i_accs,
const OpenHRP::dSequenceSequence  i_zmps,
const OpenHRP::dSequenceSequence  i_wrenches,
const OpenHRP::dSequenceSequence  i_optionals,
const dSequence  i_tms 
)

Definition at line 519 of file SequencePlayer.cpp.

bool SequencePlayer::setJointAnglesSequenceOfGroup ( const char *  gname,
const OpenHRP::dSequenceSequence  angless,
const OpenHRP::dSequence &  times 
)

Definition at line 489 of file SequencePlayer.cpp.

void SequencePlayer::setMaxIKError ( double  pos,
double  rot 
)

Definition at line 884 of file SequencePlayer.cpp.

Definition at line 889 of file SequencePlayer.cpp.

bool SequencePlayer::setTargetPose ( const char *  gname,
const double *  xyz,
const double *  rpy,
double  tm,
const char *  frame_name 
)

Definition at line 581 of file SequencePlayer.cpp.

bool SequencePlayer::setWrenches ( const double *  wrenches,
double  tm 
)

Definition at line 574 of file SequencePlayer.cpp.

bool SequencePlayer::setZmp ( const double *  zmp,
double  tm 
)

Definition at line 564 of file SequencePlayer.cpp.

Definition at line 366 of file SequencePlayer.cpp.

Definition at line 375 of file SequencePlayer.cpp.


Member Data Documentation

Definition at line 95 of file SequencePlayer.h.

Definition at line 198 of file SequencePlayer.h.

TimedAcceleration3D SequencePlayer::m_accRef [protected]

Definition at line 152 of file SequencePlayer.h.

OutPort<TimedAcceleration3D> SequencePlayer::m_accRefOut [protected]

Definition at line 153 of file SequencePlayer.h.

TimedPoint3D SequencePlayer::m_basePos [protected]

Definition at line 154 of file SequencePlayer.h.

TimedPoint3D SequencePlayer::m_basePosInit [protected]

Definition at line 135 of file SequencePlayer.h.

InPort<TimedPoint3D> SequencePlayer::m_basePosInitIn [protected]

Definition at line 136 of file SequencePlayer.h.

OutPort<TimedPoint3D> SequencePlayer::m_basePosOut [protected]

Definition at line 155 of file SequencePlayer.h.

TimedOrientation3D SequencePlayer::m_baseRpy [protected]

Definition at line 156 of file SequencePlayer.h.

TimedOrientation3D SequencePlayer::m_baseRpyInit [protected]

Definition at line 137 of file SequencePlayer.h.

InPort<TimedOrientation3D> SequencePlayer::m_baseRpyInitIn [protected]

Definition at line 138 of file SequencePlayer.h.

OutPort<TimedOrientation3D> SequencePlayer::m_baseRpyOut [protected]

Definition at line 157 of file SequencePlayer.h.

Definition at line 185 of file SequencePlayer.h.

unsigned int SequencePlayer::m_debugLevel [private]

Definition at line 189 of file SequencePlayer.h.

double SequencePlayer::m_error_pos [private]

Definition at line 192 of file SequencePlayer.h.

double SequencePlayer::m_error_rot [private]

Definition at line 192 of file SequencePlayer.h.

std::string SequencePlayer::m_fixedLink [private]

Definition at line 194 of file SequencePlayer.h.

Definition at line 195 of file SequencePlayer.h.

Definition at line 196 of file SequencePlayer.h.

std::string SequencePlayer::m_gname [private]

Definition at line 188 of file SequencePlayer.h.

short SequencePlayer::m_iteration [private]

Definition at line 193 of file SequencePlayer.h.

Definition at line 191 of file SequencePlayer.h.

Definition at line 195 of file SequencePlayer.h.

Definition at line 196 of file SequencePlayer.h.

TimedDoubleSeq SequencePlayer::m_optionalData [protected]

Definition at line 160 of file SequencePlayer.h.

OutPort<TimedDoubleSeq> SequencePlayer::m_optionalDataOut [protected]

Definition at line 161 of file SequencePlayer.h.

TimedDoubleSeq SequencePlayer::m_qInit [protected]

Definition at line 133 of file SequencePlayer.h.

InPort<TimedDoubleSeq> SequencePlayer::m_qInitIn [protected]

Definition at line 134 of file SequencePlayer.h.

TimedDoubleSeq SequencePlayer::m_qRef [protected]

Definition at line 146 of file SequencePlayer.h.

OutPort<TimedDoubleSeq> SequencePlayer::m_qRefOut [protected]

Definition at line 147 of file SequencePlayer.h.

Definition at line 187 of file SequencePlayer.h.

Definition at line 184 of file SequencePlayer.h.

Definition at line 168 of file SequencePlayer.h.

Definition at line 174 of file SequencePlayer.h.

Definition at line 197 of file SequencePlayer.h.

TimedDoubleSeq SequencePlayer::m_tqRef [protected]

Definition at line 148 of file SequencePlayer.h.

OutPort<TimedDoubleSeq> SequencePlayer::m_tqRefOut [protected]

Definition at line 149 of file SequencePlayer.h.

Definition at line 185 of file SequencePlayer.h.

sem_t SequencePlayer::m_waitSem [private]

Definition at line 186 of file SequencePlayer.h.

std::vector<TimedDoubleSeq> SequencePlayer::m_wrenches [protected]

Definition at line 158 of file SequencePlayer.h.

std::vector<OutPort<TimedDoubleSeq> *> SequencePlayer::m_wrenchesOut [protected]

Definition at line 159 of file SequencePlayer.h.

TimedPoint3D SequencePlayer::m_zmpRef [protected]

Definition at line 150 of file SequencePlayer.h.

TimedPoint3D SequencePlayer::m_zmpRefInit [protected]

Definition at line 139 of file SequencePlayer.h.

InPort<TimedPoint3D> SequencePlayer::m_zmpRefInitIn [protected]

Definition at line 140 of file SequencePlayer.h.

OutPort<TimedPoint3D> SequencePlayer::m_zmpRefOut [protected]

Definition at line 151 of file SequencePlayer.h.

Definition at line 190 of file SequencePlayer.h.


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


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed Sep 6 2017 02:35:58