Classes | |
class | AbstractVrmlGroup |
class | AccelSensor |
class | Body |
struct | BodyCustomizerInterface |
struct | BodyHandleEntity |
struct | BodyInterface |
class | CFSImpl |
class | ColdetLinkPair |
class | ColdetModel |
class | ColdetModelPair |
class | ColdetModelSharedDataSet |
class | collision_data |
class | CollisionPairInserter |
class | CollisionPairInserterBase |
class | ConstraintForceSolver |
class | CustomizedJointPath |
class | EasyScanner |
class | Edge |
class | ForceSensor |
class | ForwardDynamics |
class | ForwardDynamicsABM |
class | ForwardDynamicsMM |
class | ImageConverter |
class | InverseKinematics |
class | JointNodeSet |
class | JointPath |
class | Light |
class | Link |
class | LinkPath |
class | LinkTraverse |
class | ModelNodeSet |
class | ModelNodeSetImpl |
class | RangeSensor |
class | RateGyroSensor |
class | Referenced |
class | Sensor |
struct | SFImage |
class | TMSImpl |
struct | triangle3 |
class | TriangleMeshShaper |
struct | trianglePair |
class | Triangulator |
class | VisionSensor |
class | VrmlAnchor |
class | VrmlAppearance |
VRML Appearance node. More... | |
class | VrmlBackground |
VRML Background node. More... | |
class | VrmlBillboard |
class | VrmlBox |
VRML Box node. More... | |
class | VrmlCollision |
class | VrmlColor |
VRML Color node. More... | |
class | VrmlCone |
VRML Cone node. More... | |
class | VrmlCoordinate |
VRML Coordinate node. More... | |
class | VrmlCylinder |
VRML Cylinder node. More... | |
class | VrmlCylinderSensor |
VRML CylinderSensor node. More... | |
class | VrmlDirectionalLight |
class | VrmlElevationGrid |
VRML ElevationGrid node. More... | |
class | VrmlExtrusion |
VRML Extrusion node. More... | |
class | VrmlFog |
class | VrmlFontStyle |
VRML FontStyle node. More... | |
class | VrmlGeometry |
Base class of VRML geometry nodes. More... | |
class | VrmlGroup |
VRML Group node. More... | |
class | VrmlImageTexture |
VRML ImageTexture node. More... | |
class | VrmlIndexedFaceSet |
VRML IndexedFaseSet node. More... | |
class | VrmlIndexedLineSet |
VRML IndexedLineSet node. More... | |
class | VrmlInline |
VRML Inline node. More... | |
class | VrmlLOD |
class | VrmlMaterial |
VRML Material node. More... | |
class | VrmlMovieTexture |
VRML MovieTexture node. More... | |
class | VrmlNavigationInfo |
VRML NavigationInfo node. More... | |
class | VrmlNode |
Abstract base class of all vrml nodes. More... | |
class | VrmlNormal |
VRML Normal node. More... | |
class | VrmlParser |
Parser for VRML97 format. More... | |
class | VrmlParserImpl |
class | VrmlPixelTexture |
VRML PixelTexture node. More... | |
class | VrmlPointLight |
class | VrmlPointSet |
VRML PointSet node. More... | |
class | VrmlProto |
VRML Proto definition. More... | |
class | VrmlProtoInstance |
VRML node which is instance of VRML Prototype. More... | |
class | VrmlShape |
VRML Shape node. More... | |
class | VrmlSphere |
VRML Sphere node. More... | |
class | VrmlSpotLight |
class | VrmlSwitch |
class | VrmlText |
VRML Text node. More... | |
class | VrmlTexture |
Base class of VRML Texture nodes. More... | |
class | VrmlTextureCoordinate |
VRML TextureCoordinate node. More... | |
class | VrmlTextureTransform |
VRML TextureTransform node. More... | |
class | VrmlTransform |
VRML Transform node. More... | |
class | VrmlUnsupportedNode |
class | VrmlVariantField |
class | VrmlViewpoint |
VRML Viewpoint node. More... | |
class | VrmlWorldInfo |
class | VrmlWriter |
class | World |
class | WorldBase |
Typedefs | |
typedef boost::intrusive_ptr< AbstractVrmlGroup > | AbstractVrmlGroupPtr |
typedef bool(* | BodyCustomizerCalcAnalyticIkFunc) (BodyCustomizerHandle customizerHandle, int ikPathId, const Vector3 &p, const Matrix33 &R) |
typedef BodyCustomizerHandle(* | BodyCustomizerCreateFunc) (BodyHandle bodyHandle, const char *modelName) |
typedef void(* | BodyCustomizerDestroyFunc) (BodyCustomizerHandle customizerHandle) |
typedef void * | BodyCustomizerHandle |
typedef int(* | BodyCustomizerInitializeAnalyticIkFunc) (BodyCustomizerHandle customizerHandle, int baseLinkIndex, int targetLinkIndex) |
typedef void(* | BodyCustomizerSetVirtualJointForcesFunc) (BodyCustomizerHandle customizerHandle) |
typedef double *(* | BodyGetLinkDoubleValuePtrFunc) (BodyHandle bodyHandle, int linkIndex) |
typedef int(* | BodyGetLinkIndexFromNameFunc) (BodyHandle bodyHandle, const char *linkName) |
typedef void * | BodyHandle |
typedef boost::shared_ptr< Body > | BodyPtr |
typedef boost::intrusive_ptr< ColdetLinkPair > | ColdetLinkPairPtr |
typedef boost::intrusive_ptr< ColdetModelPair > | ColdetModelPairPtr |
typedef boost::intrusive_ptr< ColdetModel > | ColdetModelPtr |
typedef Eigen::MatrixXd | dmatrix |
typedef Eigen::Quaternion< double > | dquaternion |
typedef Eigen::VectorXd | dvector |
typedef Eigen::Matrix< double, 6, 1 > | dvector6 |
typedef boost::shared_ptr< EasyScanner > | EasyScannerPtr |
typedef std::map< Edge, trianglePair > | EdgeToTriangleMap |
typedef boost::shared_ptr< ForwardDynamicsMM > | ForwardDynamicsMMPtr |
typedef boost::shared_ptr< ForwardDynamics > | ForwardDynamicsPtr |
typedef BodyCustomizerInterface *(* | GetBodyCustomizerInterfaceFunc) (BodyInterface *bodyInterface) |
typedef boost::shared_ptr< InverseKinematics > | IInverseKinematicsPtr |
typedef Eigen::VectorXi | ivector |
typedef std::vector< JointNodeSetPtr > | JointNodeSetArray |
typedef boost::shared_ptr< JointNodeSet > | JointNodeSetPtr |
typedef boost::shared_ptr< JointPath > | JointPathPtr |
typedef Eigen::Matrix3d | Matrix33 |
typedef Eigen::Matrix4d | Matrix44 |
typedef std::vector< SFColor > | MFColor |
typedef std::vector< SFFloat > | MFFloat |
typedef std::vector< SFInt32 > | MFInt32 |
typedef std::vector< SFNode > | MFNode |
typedef std::vector< SFRotation > | MFRotation |
typedef std::vector< SFString > | MFString |
typedef std::vector< SFTime > | MFTime |
typedef std::vector< SFVec2f > | MFVec2f |
typedef std::vector< SFVec3f > | MFVec3f |
typedef std::vector< SFVec4f > | MFVec4f |
typedef boost::shared_ptr< ModelNodeSet > | ModelNodeSetPtr |
typedef bool | SFBool |
typedef SFVec3f | SFColor |
typedef double | SFFloat |
typedef int | SFInt32 |
typedef VrmlNodePtr | SFNode |
typedef SFVec4f | SFRotation |
typedef std::string | SFString |
typedef SFFloat | SFTime |
typedef boost::array< SFFloat, 2 > | SFVec2f |
typedef boost::array< SFFloat, 3 > | SFVec3f |
typedef boost::array< SFFloat, 4 > | SFVec4f |
typedef std::map< std::string, VrmlVariantField > | TProtoFieldMap |
typedef std::pair< std::string, VrmlVariantField > | TProtoFieldPair |
typedef Eigen::Vector2d | Vector2 |
typedef Eigen::Vector3d | Vector3 |
typedef Eigen::Vector3d | Vector3Ref |
typedef Eigen::Vector4d | Vector4 |
typedef boost::intrusive_ptr< VrmlAnchor > | VrmlAnchorPtr |
typedef boost::intrusive_ptr< VrmlAppearance > | VrmlAppearancePtr |
typedef boost::intrusive_ptr< VrmlBackground > | VrmlBackgroundPtr |
typedef boost::intrusive_ptr< VrmlBillboard > | VrmlBillboardPtr |
typedef boost::intrusive_ptr< VrmlBox > | VrmlBoxPtr |
typedef boost::intrusive_ptr< VrmlCollision > | VrmlCollisionPtr |
typedef boost::intrusive_ptr< VrmlColor > | VrmlColorPtr |
typedef boost::intrusive_ptr< VrmlCone > | VrmlConePtr |
typedef boost::intrusive_ptr< VrmlCoordinate > | VrmlCoordinatePtr |
typedef boost::intrusive_ptr< VrmlCylinder > | VrmlCylinderPtr |
typedef boost::intrusive_ptr< VrmlCylinderSensor > | VrmlCylinderSensorPtr |
typedef boost::intrusive_ptr< VrmlDirectionalLight > | VrmlDirectionalLightPtr |
typedef boost::intrusive_ptr< VrmlElevationGrid > | VrmlElevationGridPtr |
typedef boost::intrusive_ptr< VrmlExtrusion > | VrmlExtrusionPtr |
typedef boost::intrusive_ptr< VrmlFog > | VrmlFogPtr |
typedef boost::intrusive_ptr< VrmlFontStyle > | VrmlFontStylePtr |
typedef boost::intrusive_ptr< VrmlGeometry > | VrmlGeometryPtr |
typedef boost::intrusive_ptr< VrmlGroup > | VrmlGroupPtr |
typedef boost::intrusive_ptr< VrmlImageTexture > | VrmlImageTexturePtr |
typedef boost::intrusive_ptr< VrmlIndexedFaceSet > | VrmlIndexedFaceSetPtr |
typedef boost::intrusive_ptr< VrmlIndexedLineSet > | VrmlIndexedLineSetPtr |
typedef boost::intrusive_ptr< VrmlInline > | VrmlInlinePtr |
typedef boost::intrusive_ptr< VrmlLOD > | VrmlLODPtr |
typedef boost::intrusive_ptr< VrmlMaterial > | VrmlMaterialPtr |
typedef boost::intrusive_ptr< VrmlMovieTexture > | VrmlMovieTexturePtr |
typedef boost::intrusive_ptr< VrmlNavigationInfo > | VrmlNavigationInfoPtr |
typedef boost::intrusive_ptr< VrmlNode > | VrmlNodePtr |
typedef boost::intrusive_ptr< VrmlNormal > | VrmlNormalPtr |
typedef boost::intrusive_ptr< VrmlPixelTexture > | VrmlPixelTexturePtr |
typedef boost::intrusive_ptr< VrmlPointLight > | VrmlPointLightPtr |
typedef boost::intrusive_ptr< VrmlPointSet > | VrmlPointSetPtr |
typedef boost::intrusive_ptr< VrmlProtoInstance > | VrmlProtoInstancePtr |
typedef boost::intrusive_ptr< VrmlProto > | VrmlProtoPtr |
typedef boost::intrusive_ptr< VrmlShape > | VrmlShapePtr |
typedef boost::intrusive_ptr< VrmlSphere > | VrmlSpherePtr |
typedef boost::intrusive_ptr< VrmlSpotLight > | VrmlSpotLightPtr |
typedef boost::intrusive_ptr< VrmlSwitch > | VrmlSwitchPtr |
typedef boost::intrusive_ptr< VrmlText > | VrmlTextPtr |
typedef boost::intrusive_ptr< VrmlTextureCoordinate > | VrmlTextureCoordinatePtr |
typedef boost::intrusive_ptr< VrmlTexture > | VrmlTexturePtr |
typedef boost::intrusive_ptr< VrmlTextureTransform > | VrmlTextureTransformPtr |
typedef boost::intrusive_ptr< VrmlTransform > | VrmlTransformPtr |
typedef boost::intrusive_ptr< VrmlUnsupportedNode > | VrmlUnsupportedNodePtr |
typedef boost::intrusive_ptr< VrmlViewpoint > | VrmlViewpointPtr |
typedef boost::intrusive_ptr< VrmlWorldInfo > | VrmlWorldInfoPtr |
typedef void(VrmlWriter::* | VrmlWriterNodeMethod) (VrmlNodePtr node) |
Enumerations | |
enum | { LEFT, TOP, FRONT, BOTTOM, RIGHT, BACK } |
enum | VrmlFieldTypeId { UNDETERMINED_FIELD_TYPE = 0, SFBOOL, SFINT32, MFINT32, SFFLOAT, MFFLOAT, SFVEC2F, MFVEC2F, SFVEC3F, MFVEC3F, SFROTATION, MFROTATION, SFTIME, MFTIME, SFCOLOR, MFCOLOR, SFSTRING, MFSTRING, SFNODE, MFNODE, SFIMAGE } |
enum | VrmlNodeCategory { ANY_NODE = -1, PROTO_DEF_NODE = 0, PROTO_INSTANCE_NODE, TOP_NODE, BINDABLE_NODE, GROUPING_NODE, CHILD_NODE, APPEARANCE_NODE, MATERIAL_NODE, TEXTURE_NODE, TEXTURE_TRANSFORM_NODE, SHAPE_NODE, GEOMETRY_NODE, COORDINATE_NODE, COLOR_NODE, NORMAL_NODE, TEXTURE_COORDINATE_NODE, FONT_STYLE_NODE, SENSOR_NODE, INLINE_NODE, LIGHT_NODE, NUM_VRML_NODE_CATEGORIES } |
Functions | |
int | calcEigenVectors (const dmatrix &_a, dmatrix &_evec, dvector &_eval) |
void | calcInverse (Matrix33 &inv, const Matrix33 &m) |
int | calcPseudoInverse (const dmatrix &_a, dmatrix &_a_pseu, double _sv_ratio) |
HRP_UTIL_EXPORT void | calcRodrigues (Matrix33 &out_R, const Vector3 &axis, double q) |
HRP_UTIL_EXPORT void | calcRodrigues (Matrix44 &out_R, const Vector3 &axis, double q) |
HRP_UTIL_EXPORT void | calcRotFromRpy (Matrix33 &out_R, double r, double p, double y) |
int | calcSRInverse (const dmatrix &_a, dmatrix &_a_sr, double _sr_ratio, dmatrix _w) |
HRP_UTIL_EXPORT void | calcTransformMatrix (VrmlTransform *transform, Matrix44 &out_T) |
Vector3 | cross (const Vector3 &v1, const Vector3 &v2) |
def | degrees (x) |
HRP_UTIL_EXPORT string | deleteURLScheme (string url) |
double | det (const dmatrix &_a) |
double | dot (const Vector3 &v1, const Vector3 &v2) |
template<class VrmlNodeType > | |
boost::intrusive_ptr< VrmlNodeType > | dynamic_node_cast (VrmlNodePtr node) |
HRPMODEL_API BodyCustomizerInterface * | findBodyCustomizer (std::string modelName) |
def | findCollisionDetectorFactory (rnc=None) |
def | findControllerFactory (name, rnc=None) |
def | findDynamicsPlugin (name, rnc=None) |
def | findDynamicsSimulatorFactory (rnc=None) |
def | findIoControlPlugin (name, rnc=None) |
def | findLogPlugin (name, rnc=None) |
def | findModelLoader (rnc=None) |
def | findObject (objname, rnc=None) |
def | findOnlineViewer (rnc=None) |
def | findPlugin (name, rnc=None) |
def | findPluginManager (name, rnc=None) |
def | findPositionSensor (rnc=None) |
def | findReceiver (objname, rnc=None) |
def | findSeqPlugin (name, rnc=None) |
def | findSpeakServer (rnc=None) |
def | findStabilizerPlugin (name, rnc=None) |
def | findStateProvider (name, rnc=None) |
def | findStereoVision (rnc=None) |
def | findWalkPlugin (name, rnc=None) |
template<class Array > | |
void | getMatrix33FromRowMajorArray (Matrix33 &m33, const Array &a, size_t top=0) |
HRPMODEL_API OpenHRP::ModelLoader_var | getModelLoader (CORBA_ORB_var orb) |
HRPMODEL_API OpenHRP::ModelLoader_var | getModelLoader (CosNaming::NamingContext_var cxt) |
HRP_UTIL_EXPORT OpenHRP::OnlineViewer_var | getOnlineViewer (CORBA_ORB_var orb) |
HRP_UTIL_EXPORT OpenHRP::OnlineViewer_var | getOnlineViewer (CosNaming::NamingContext_var cxt) |
HRP_UTIL_EXPORT OpenHRP::OnlineViewer_var | getOnlineViewer (int argc, char **argv) |
HRP_UTIL_EXPORT void | getPathFromUrl (string &refUrl, const string &rootDir, string srcUrl) |
def | getRootNamingContext (corbaloc) |
template<class M > | |
void | getVector3 (Vector3 &v3, const M &m, size_t row, size_t col) |
template<class V > | |
void | getVector3 (Vector3 &v3, const V &v, size_t top=0) |
Vector3Ref | getVector3Ref (const double *data) |
Matrix33 | hat (const Vector3 &c) |
def | initCORBA () |
void | intrusive_ptr_add_ref (Referenced *obj) |
void | intrusive_ptr_add_ref (VrmlNode *obj) |
void | intrusive_ptr_release (Referenced *obj) |
void | intrusive_ptr_release (VrmlNode *obj) |
dmatrix | inverse (const dmatrix &M) |
Matrix33 | inverse (const Matrix33 &m) |
HRP_UTIL_EXPORT Matrix33 | inverse33 (const Matrix33 &m) |
HRP_UTIL_EXPORT bool | isFileProtocol (const string &ref) |
HRP_UTIL_EXPORT bool | isOrthogonalMatrix (Matrix33 &m) |
HRPMODEL_API int | loadBodyCustomizers () |
HRPMODEL_API int | loadBodyCustomizers (BodyInterface *bodyInterface) |
HRPMODEL_API int | loadBodyCustomizers (const std::string pathString) |
HRPMODEL_API int | loadBodyCustomizers (const std::string pathString, BodyInterface *bodyInterface) |
HRPMODEL_API bool | loadBodyFromBodyInfo (BodyPtr body, OpenHRP::BodyInfo_ptr bodyInfo, bool loadGeometryForCollisionDetection=false, Link *(*f)()=NULL) |
HRPMODEL_API bool | loadBodyFromModelLoader (BodyPtr body, const char *url, CORBA_ORB_var orb, bool loadGeometryForCollisionDetection=false) |
HRPMODEL_API bool | loadBodyFromModelLoader (BodyPtr body, const char *url, CosNaming::NamingContext_var cxt, bool loadGeometryForCollisionDetection=false) |
HRPMODEL_API bool | loadBodyFromModelLoader (BodyPtr body, const char *url, int &argc, char *argv[], bool loadGeometryForCollisionDetection=false) |
HRPMODEL_API OpenHRP::BodyInfo_var | loadBodyInfo (const char *url, CORBA_ORB_var orb) |
HRPMODEL_API OpenHRP::BodyInfo_var | loadBodyInfo (const char *url, CosNaming::NamingContext_var cxt) |
HRPMODEL_API OpenHRP::BodyInfo_var | loadBodyInfo (const char *url, int &argc, char *argv[]) |
def | loadVRML (url) |
static int | max (int a, int b) |
static int | min (int a, int b) |
Vector3 | nomralize (const Vector3 &v) |
double | norm2 (const Vector3 &v) |
HRP_UTIL_EXPORT Vector3 | omegaFromRot (const Matrix33 &r) |
HRP_UTIL_EXPORT EasyScanner & | operator>> (EasyScanner &scanner, char matchChar) |
HRP_UTIL_EXPORT EasyScanner & | operator>> (EasyScanner &scanner, const char *matchString) |
HRP_UTIL_EXPORT EasyScanner & | operator>> (EasyScanner &scanner, double &value) |
HRP_UTIL_EXPORT EasyScanner & | operator>> (EasyScanner &scanner, EasyScanner::Endl endl) |
HRP_UTIL_EXPORT EasyScanner & | operator>> (EasyScanner &scanner, int &value) |
HRP_UTIL_EXPORT EasyScanner & | operator>> (EasyScanner &scanner, std::string &str) |
def | radians (x) |
Matrix33 | rodrigues (const Vector3 &axis, double q) |
Matrix33 | rotationX (double theta) |
Matrix33 | rotationY (double theta) |
Matrix33 | rotationZ (double theta) |
Matrix33 | rotFromRpy (const Vector3 &rpy) |
Matrix33 | rotFromRpy (double r, double p, double y) |
HRP_UTIL_EXPORT Vector3 | rpyFromRot (const Matrix33 &m) |
template<class M > | |
void | setMatrix33 (const Matrix33 &m33, M &m, size_t row=0, size_t col=0) |
template<class Array > | |
void | setMatrix33ToRowMajorArray (const Matrix33 &m33, Array &a, size_t top=0) |
template<class M > | |
void | setTransMatrix33 (const Matrix33 &m33, M &m, size_t row=0, size_t col=0) |
template<class V > | |
void | setVector3 (const Vector3 &v3, const V &v, size_t top=0) |
template<class M > | |
void | setVector3 (const Vector3 &v3, M &m, size_t row, size_t col) |
template<class V > | |
void | setVector3 (const Vector3 &v3, V &v, size_t top=0) |
int | solveLinearEquation (const dmatrix &_a, const dvector &_b, dvector &_x, double _sv_ratio) |
int | solveLinearEquationLU (const dmatrix &_a, const dvector &_b, dvector &_x) |
int | solveLinearEquationLU (dmatrix a, const dmatrix &b, dmatrix &out_x) |
int | solveLinearEquationSVD (const dmatrix &_a, const dvector &_b, dvector &_x, double _sv_ratio) |
Matrix33 | trans (const Matrix33 &m) |
def | unbindObject (objname) |
Matrix33 | VVt_prod (const Vector3 &a, const Vector3 &b) |
Variables | |
static const int | BODY_CUSTOMIZER_INTERFACE_VERSION = 1 |
static const int | BODY_INTERFACE_VERSION = 1 |
const typedef char **(* | BodyCustomizerGetTargetModelNamesFunc )() |
const typedef char *(* | BodyGetLinkNameFunc )(BodyHandle bodyHandle, int linkIndex) |
rootnc = None | |
typedef boost::intrusive_ptr<AbstractVrmlGroup> hrp::AbstractVrmlGroupPtr |
Definition at line 232 of file VrmlNodes.h.
typedef bool(* hrp::BodyCustomizerCalcAnalyticIkFunc) (BodyCustomizerHandle customizerHandle, int ikPathId, const Vector3 &p, const Matrix33 &R) |
Definition at line 53 of file BodyCustomizerInterface.h.
typedef BodyCustomizerHandle(* hrp::BodyCustomizerCreateFunc) (BodyHandle bodyHandle, const char *modelName) |
Definition at line 45 of file BodyCustomizerInterface.h.
typedef void(* hrp::BodyCustomizerDestroyFunc) (BodyCustomizerHandle customizerHandle) |
Definition at line 47 of file BodyCustomizerInterface.h.
typedef void * hrp::BodyCustomizerHandle |
typedef int(* hrp::BodyCustomizerInitializeAnalyticIkFunc) (BodyCustomizerHandle customizerHandle, int baseLinkIndex, int targetLinkIndex) |
Definition at line 48 of file BodyCustomizerInterface.h.
typedef void(* hrp::BodyCustomizerSetVirtualJointForcesFunc) (BodyCustomizerHandle customizerHandle) |
Definition at line 55 of file BodyCustomizerInterface.h.
typedef double*(* hrp::BodyGetLinkDoubleValuePtrFunc) (BodyHandle bodyHandle, int linkIndex) |
Definition at line 29 of file BodyCustomizerInterface.h.
typedef int(* hrp::BodyGetLinkIndexFromNameFunc) (BodyHandle bodyHandle, const char *linkName) |
Definition at line 27 of file BodyCustomizerInterface.h.
typedef void * hrp::BodyHandle |
typedef boost::shared_ptr< Body > hrp::BodyPtr |
typedef boost::intrusive_ptr<ColdetLinkPair> hrp::ColdetLinkPairPtr |
Definition at line 35 of file ColdetLinkPair.h.
typedef boost::intrusive_ptr<ColdetModelPair> hrp::ColdetModelPairPtr |
Definition at line 124 of file ColdetModelPair.h.
typedef boost::intrusive_ptr< ColdetModel > hrp::ColdetModelPtr |
Definition at line 268 of file ColdetModel.h.
typedef Eigen::MatrixXd hrp::dmatrix |
Definition at line 13 of file EigenTypes.h.
typedef Eigen::Quaternion<double> hrp::dquaternion |
Definition at line 17 of file EigenTypes.h.
typedef Eigen::VectorXd hrp::dvector |
Definition at line 14 of file EigenTypes.h.
typedef Eigen::Matrix<double, 6,1> hrp::dvector6 |
Definition at line 16 of file EigenTypes.h.
typedef boost::shared_ptr<EasyScanner> hrp::EasyScannerPtr |
Definition at line 280 of file EasyScanner.h.
typedef std::map< Edge, trianglePair > hrp::EdgeToTriangleMap |
Definition at line 59 of file ColdetModel.h.
typedef boost::shared_ptr<ForwardDynamicsMM> hrp::ForwardDynamicsMMPtr |
Definition at line 157 of file ForwardDynamicsCBM.h.
typedef boost::shared_ptr<ForwardDynamics> hrp::ForwardDynamicsPtr |
Definition at line 92 of file ForwardDynamics.h.
typedef BodyCustomizerInterface*(* hrp::GetBodyCustomizerInterfaceFunc) (BodyInterface *bodyInterface) |
Definition at line 72 of file BodyCustomizerInterface.h.
typedef boost::shared_ptr<InverseKinematics> hrp::IInverseKinematicsPtr |
Definition at line 29 of file InverseKinematics.h.
typedef Eigen::VectorXi hrp::ivector |
Definition at line 15 of file EigenTypes.h.
typedef std::vector<JointNodeSetPtr> hrp::JointNodeSetArray |
Definition at line 50 of file ModelNodeSet.h.
typedef boost::shared_ptr<JointNodeSet> hrp::JointNodeSetPtr |
Definition at line 34 of file ModelNodeSet.h.
typedef boost::shared_ptr< JointPath > hrp::JointPathPtr |
typedef Eigen::Matrix3d hrp::Matrix33 |
Definition at line 12 of file EigenTypes.h.
typedef Eigen::Matrix4d hrp::Matrix44 |
typedef std::vector<SFColor> hrp::MFColor |
Definition at line 76 of file VrmlNodes.h.
typedef std::vector<SFFloat> hrp::MFFloat |
Definition at line 70 of file VrmlNodes.h.
typedef std::vector<SFInt32> hrp::MFInt32 |
Definition at line 69 of file VrmlNodes.h.
typedef std::vector<SFNode> hrp::MFNode |
Definition at line 158 of file VrmlNodes.h.
typedef std::vector<SFRotation> hrp::MFRotation |
Definition at line 74 of file VrmlNodes.h.
typedef std::vector<SFString> hrp::MFString |
Definition at line 77 of file VrmlNodes.h.
typedef std::vector<SFTime> hrp::MFTime |
Definition at line 75 of file VrmlNodes.h.
typedef std::vector<SFVec2f> hrp::MFVec2f |
Definition at line 71 of file VrmlNodes.h.
typedef std::vector<SFVec3f> hrp::MFVec3f |
Definition at line 72 of file VrmlNodes.h.
typedef std::vector<SFVec4f> hrp::MFVec4f |
Definition at line 73 of file VrmlNodes.h.
typedef boost::shared_ptr<ModelNodeSet> hrp::ModelNodeSetPtr |
Definition at line 94 of file ModelNodeSet.h.
typedef bool hrp::SFBool |
Definition at line 48 of file VrmlNodes.h.
typedef SFVec3f hrp::SFColor |
Definition at line 58 of file VrmlNodes.h.
typedef double hrp::SFFloat |
Definition at line 50 of file VrmlNodes.h.
typedef int hrp::SFInt32 |
Definition at line 49 of file VrmlNodes.h.
typedef VrmlNodePtr hrp::SFNode |
Definition at line 157 of file VrmlNodes.h.
typedef SFVec4f hrp::SFRotation |
Definition at line 59 of file VrmlNodes.h.
typedef std::string hrp::SFString |
Definition at line 52 of file VrmlNodes.h.
typedef SFFloat hrp::SFTime |
Definition at line 51 of file VrmlNodes.h.
typedef boost::array<SFFloat, 2> hrp::SFVec2f |
Definition at line 54 of file VrmlNodes.h.
typedef boost::array<SFFloat, 3> hrp::SFVec3f |
Definition at line 55 of file VrmlNodes.h.
typedef boost::array<SFFloat, 4> hrp::SFVec4f |
Definition at line 56 of file VrmlNodes.h.
typedef std::map<std::string, VrmlVariantField> hrp::TProtoFieldMap |
Definition at line 854 of file VrmlNodes.h.
typedef std::pair<std::string, VrmlVariantField> hrp::TProtoFieldPair |
Definition at line 855 of file VrmlNodes.h.
typedef Eigen::Vector2d hrp::Vector2 |
Definition at line 10 of file EigenTypes.h.
typedef Eigen::Vector3d hrp::Vector3 |
Definition at line 11 of file EigenTypes.h.
typedef Eigen::Vector3d hrp::Vector3Ref |
typedef Eigen::Vector4d hrp::Vector4 |
typedef boost::intrusive_ptr<VrmlAnchor> hrp::VrmlAnchorPtr |
Definition at line 710 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlAppearance> hrp::VrmlAppearancePtr |
Definition at line 277 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlBackground> hrp::VrmlBackgroundPtr |
Definition at line 217 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlBillboard> hrp::VrmlBillboardPtr |
Definition at line 720 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlBox> hrp::VrmlBoxPtr |
Definition at line 379 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlCollision> hrp::VrmlCollisionPtr |
Definition at line 698 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlColor> hrp::VrmlColorPtr |
Definition at line 454 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlCone> hrp::VrmlConePtr |
Definition at line 393 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlCoordinate> hrp::VrmlCoordinatePtr |
Definition at line 457 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlCylinder> hrp::VrmlCylinderPtr |
Definition at line 408 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlCylinderSensor> hrp::VrmlCylinderSensorPtr |
Definition at line 551 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlDirectionalLight> hrp::VrmlDirectionalLightPtr |
Definition at line 773 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlElevationGrid> hrp::VrmlElevationGridPtr |
Definition at line 628 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlExtrusion> hrp::VrmlExtrusionPtr |
Definition at line 651 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlFog> hrp::VrmlFogPtr |
Definition at line 732 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlFontStyle> hrp::VrmlFontStylePtr |
Definition at line 437 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlGeometry> hrp::VrmlGeometryPtr |
Definition at line 280 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlGroup> hrp::VrmlGroupPtr |
Definition at line 250 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlImageTexture> hrp::VrmlImageTexturePtr |
Definition at line 350 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlIndexedFaceSet> hrp::VrmlIndexedFaceSetPtr |
Definition at line 498 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlIndexedLineSet> hrp::VrmlIndexedLineSetPtr |
Definition at line 472 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlInline> hrp::VrmlInlinePtr |
Definition at line 274 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlLOD> hrp::VrmlLODPtr |
Definition at line 687 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlMaterial> hrp::VrmlMaterialPtr |
Definition at line 295 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlMovieTexture> hrp::VrmlMovieTexturePtr |
Definition at line 602 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlNavigationInfo> hrp::VrmlNavigationInfoPtr |
Definition at line 197 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlNode> hrp::VrmlNodePtr |
Definition at line 155 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlNormal> hrp::VrmlNormalPtr |
Definition at line 475 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlPixelTexture> hrp::VrmlPixelTexturePtr |
Definition at line 582 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlPointLight> hrp::VrmlPointLightPtr |
Definition at line 759 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlPointSet> hrp::VrmlPointSetPtr |
Definition at line 566 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlProtoInstance> hrp::VrmlProtoInstancePtr |
Definition at line 898 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlProto> hrp::VrmlProtoPtr |
Definition at line 879 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlShape> hrp::VrmlShapePtr |
Definition at line 292 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlSphere> hrp::VrmlSpherePtr |
Definition at line 418 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlSpotLight> hrp::VrmlSpotLightPtr |
Definition at line 792 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlSwitch> hrp::VrmlSwitchPtr |
Definition at line 669 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlText> hrp::VrmlTextPtr |
Definition at line 451 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlTextureCoordinate> hrp::VrmlTextureCoordinatePtr |
Definition at line 478 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlTexture> hrp::VrmlTexturePtr |
Definition at line 298 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlTextureTransform> hrp::VrmlTextureTransformPtr |
Definition at line 301 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlTransform> hrp::VrmlTransformPtr |
Definition at line 265 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlUnsupportedNode> hrp::VrmlUnsupportedNodePtr |
Definition at line 167 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlViewpoint> hrp::VrmlViewpointPtr |
Definition at line 182 of file VrmlNodes.h.
typedef boost::intrusive_ptr<VrmlWorldInfo> hrp::VrmlWorldInfoPtr |
Definition at line 743 of file VrmlNodes.h.
typedef void(VrmlWriter::* hrp::VrmlWriterNodeMethod) (VrmlNodePtr node) |
Definition at line 29 of file hrplib/hrpUtil/VrmlWriter.h.
anonymous enum |
Enumerator | |
---|---|
LEFT | |
TOP | |
FRONT | |
BOTTOM | |
RIGHT | |
BACK |
Definition at line 67 of file TriangleMeshShaper.h.
enum hrp::VrmlFieldTypeId |
Enumerator | |
---|---|
UNDETERMINED_FIELD_TYPE | |
SFBOOL | |
SFINT32 | |
MFINT32 | |
SFFLOAT | |
MFFLOAT | |
SFVEC2F | |
MFVEC2F | |
SFVEC3F | |
MFVEC3F | |
SFROTATION | |
MFROTATION | |
SFTIME | |
MFTIME | |
SFCOLOR | |
MFCOLOR | |
SFSTRING | |
MFSTRING | |
SFNODE | |
MFNODE | |
SFIMAGE |
Definition at line 33 of file VrmlNodes.h.
Definition at line 81 of file VrmlNodes.h.
Definition at line 308 of file MatrixSolvers.cpp.
Definition at line 32 of file Tvmet2Eigen.h.
HRP_UTIL_EXPORT int hrp::calcPseudoInverse | ( | const dmatrix & | _a, |
dmatrix & | _a_pseu, | ||
double | _sv_ratio | ||
) |
calculate Pseudo-Inverse using SVD(Singular Value Decomposition) by lapack library DGESVD (_a can be non-square matrix)
Definition at line 243 of file MatrixSolvers.cpp.
Definition at line 22 of file Eigen3d.cpp.
Definition at line 16 of file Eigen4d.cpp.
Definition at line 138 of file Eigen3d.cpp.
HRP_UTIL_EXPORT int hrp::calcSRInverse | ( | const dmatrix & | _a, |
dmatrix & | _a_sr, | ||
double | _sr_ratio, | ||
dmatrix | _w | ||
) |
Definition at line 342 of file MatrixSolvers.cpp.
void hrp::calcTransformMatrix | ( | VrmlTransform * | transform, |
Matrix44 & | out_T | ||
) |
Definition at line 49 of file Eigen4d.cpp.
Definition at line 15 of file Tvmet2Eigen.h.
string hrp::deleteURLScheme | ( | string | url | ) |
Definition at line 25 of file UrlUtil.cpp.
HRP_UTIL_EXPORT double hrp::det | ( | const dmatrix & | _a | ) |
Definition at line 368 of file MatrixSolvers.cpp.
Definition at line 19 of file Tvmet2Eigen.h.
boost::intrusive_ptr<VrmlNodeType> hrp::dynamic_node_cast | ( | VrmlNodePtr | node | ) |
The upper cast operation that supports the situation where the original pointer is VrmlProtoInstance and you want to get the actual node, the node replaced with the pre-defined node type written in the PROTO definition.
Definition at line 907 of file VrmlNodes.h.
BodyCustomizerInterface * hrp::findBodyCustomizer | ( | std::string | modelName | ) |
Definition at line 287 of file BodyCustomizerInterface.cpp.
ModelLoader_var hrp::getModelLoader | ( | CORBA_ORB_var | orb | ) |
Definition at line 651 of file hrplib/hrpModel/ModelLoaderUtil.cpp.
ModelLoader_var hrp::getModelLoader | ( | CosNaming::NamingContext_var | cxt | ) |
Definition at line 664 of file hrplib/hrpModel/ModelLoaderUtil.cpp.
OnlineViewer_var hrp::getOnlineViewer | ( | CORBA_ORB_var | orb | ) |
Definition at line 47 of file hrpUtil/OnlineViewerUtil.cpp.
OnlineViewer_var hrp::getOnlineViewer | ( | CosNaming::NamingContext_var | cxt | ) |
Definition at line 15 of file hrpUtil/OnlineViewerUtil.cpp.
OnlineViewer_var hrp::getOnlineViewer | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 61 of file hrpUtil/OnlineViewerUtil.cpp.
Definition at line 57 of file UrlUtil.cpp.
|
inline |
|
inline |
Definition at line 31 of file Referenced.h.
Definition at line 144 of file VrmlNodes.h.
|
inline |
Definition at line 35 of file Referenced.h.
Definition at line 148 of file VrmlNodes.h.
Definition at line 37 of file MatrixSolvers.h.
Definition at line 40 of file Tvmet2Eigen.h.
|
inline |
Definition at line 46 of file Tvmet2Eigen.h.
bool hrp::isFileProtocol | ( | const string & | ref | ) |
Definition at line 105 of file UrlUtil.cpp.
bool hrp::isOrthogonalMatrix | ( | Matrix33 & | m | ) |
Definition at line 152 of file Eigen3d.cpp.
int hrp::loadBodyCustomizers | ( | ) |
Definition at line 281 of file BodyCustomizerInterface.cpp.
int hrp::loadBodyCustomizers | ( | BodyInterface * | bodyInterface | ) |
The function loads the customizers in the directories specified by the environmental variable HRPMODEL_CUSTOMIZER_PATH
Definition at line 242 of file BodyCustomizerInterface.cpp.
Definition at line 232 of file BodyCustomizerInterface.cpp.
int hrp::loadBodyCustomizers | ( | const std::string | pathString, |
BodyInterface * | bodyInterface | ||
) |
DLLs of body customizer in the path are loaded and they are registered to the customizer repository.
The loaded customizers can be obtained by using hrp::findBodyCustomizer() function.
pathString | the path to a DLL file or a directory that contains DLLs |
bodyInterface |
Definition at line 147 of file BodyCustomizerInterface.cpp.
bool hrp::loadBodyFromBodyInfo | ( | BodyPtr | body, |
OpenHRP::BodyInfo_ptr | bodyInfo, | ||
bool | loadGeometryForCollisionDetection = false , |
||
Link *(*)() | f = NULL |
||
) |
Definition at line 619 of file hrplib/hrpModel/ModelLoaderUtil.cpp.
bool hrp::loadBodyFromModelLoader | ( | BodyPtr | body, |
const char * | url, | ||
CORBA_ORB_var | orb, | ||
bool | loadGeometryForCollisionDetection = false |
||
) |
Definition at line 730 of file hrplib/hrpModel/ModelLoaderUtil.cpp.
bool hrp::loadBodyFromModelLoader | ( | BodyPtr | body, |
const char * | url, | ||
CosNaming::NamingContext_var | cxt, | ||
bool | loadGeometryForCollisionDetection = false |
||
) |
Definition at line 714 of file hrplib/hrpModel/ModelLoaderUtil.cpp.
bool hrp::loadBodyFromModelLoader | ( | BodyPtr | body, |
const char * | url, | ||
int & | argc, | ||
char * | argv[], | ||
bool | loadGeometryForCollisionDetection = false |
||
) |
Definition at line 745 of file hrplib/hrpModel/ModelLoaderUtil.cpp.
BodyInfo_var hrp::loadBodyInfo | ( | const char * | url, |
CORBA_ORB_var | orb | ||
) |
Definition at line 638 of file hrplib/hrpModel/ModelLoaderUtil.cpp.
BodyInfo_var hrp::loadBodyInfo | ( | const char * | url, |
CosNaming::NamingContext_var | cxt | ||
) |
Definition at line 699 of file hrplib/hrpModel/ModelLoaderUtil.cpp.
Definition at line 632 of file hrplib/hrpModel/ModelLoaderUtil.cpp.
Definition at line 54 of file MatrixSolvers.cpp.
Definition at line 55 of file MatrixSolvers.cpp.
Definition at line 23 of file Tvmet2Eigen.h.
Definition at line 22 of file Tvmet2Eigen.h.
Definition at line 63 of file Eigen3d.cpp.
HRP_UTIL_EXPORT EasyScanner& hrp::operator>> | ( | EasyScanner & | scanner, |
char | matchChar | ||
) |
Definition at line 779 of file EasyScanner.cpp.
HRP_UTIL_EXPORT EasyScanner& hrp::operator>> | ( | EasyScanner & | scanner, |
const char * | matchString | ||
) |
Definition at line 767 of file EasyScanner.cpp.
HRP_UTIL_EXPORT EasyScanner& hrp::operator>> | ( | EasyScanner & | scanner, |
double & | value | ||
) |
Definition at line 746 of file EasyScanner.cpp.
HRP_UTIL_EXPORT EasyScanner& hrp::operator>> | ( | EasyScanner & | scanner, |
EasyScanner::Endl | endl | ||
) |
Definition at line 800 of file EasyScanner.cpp.
HRP_UTIL_EXPORT EasyScanner& hrp::operator>> | ( | EasyScanner & | scanner, |
int & | value | ||
) |
Definition at line 756 of file EasyScanner.cpp.
HRP_UTIL_EXPORT EasyScanner& hrp::operator>> | ( | EasyScanner & | scanner, |
std::string & | str | ||
) |
|
inline |
Definition at line 99 of file Eigen3d.cpp.
HRP_UTIL_EXPORT int hrp::solveLinearEquation | ( | const dmatrix & | _a, |
const dvector & | _b, | ||
dvector & | _x, | ||
double | _sv_ratio | ||
) |
Unified interface to solve a linear equation
b = a * x, x = b^(-1) * a
Definition at line 230 of file MatrixSolvers.cpp.
HRP_UTIL_EXPORT int hrp::solveLinearEquationLU | ( | const dmatrix & | _a, |
const dvector & | _b, | ||
dvector & | _x | ||
) |
solve linear equation using LU decomposition by lapack library DGESVX (_a must be square matrix)
Definition at line 91 of file MatrixSolvers.cpp.
Definition at line 58 of file MatrixSolvers.cpp.
HRP_UTIL_EXPORT int hrp::solveLinearEquationSVD | ( | const dmatrix & | _a, |
const dvector & | _b, | ||
dvector & | _x, | ||
double | _sv_ratio | ||
) |
solve linear equation using SVD(Singular Value Decomposition) by lapack library DGESVD (_a can be non-square matrix)
Definition at line 157 of file MatrixSolvers.cpp.
Definition at line 18 of file Tvmet2Eigen.h.
Definition at line 24 of file Tvmet2Eigen.h.
Definition at line 58 of file BodyCustomizerInterface.h.
Definition at line 31 of file BodyCustomizerInterface.h.
const typedef char**(* hrp::BodyCustomizerGetTargetModelNamesFunc) () |
Definition at line 44 of file BodyCustomizerInterface.h.
const typedef char*(* hrp::BodyGetLinkNameFunc) (BodyHandle bodyHandle, int linkIndex) |
Definition at line 28 of file BodyCustomizerInterface.h.