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 const char **(* | BodyCustomizerGetTargetModelNamesFunc )() |
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 const char *(* | BodyGetLinkNameFunc )(BodyHandle bodyHandle, int linkIndex) |
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 (Matrix44 &out_R, const Vector3 &axis, double q) |
HRP_UTIL_EXPORT void | calcRodrigues (Matrix33 &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 |
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 |
def | findControllerFactory |
def | findDynamicsPlugin |
def | findDynamicsSimulatorFactory |
def | findIoControlPlugin |
def | findLogPlugin |
def | findModelLoader |
def | findObject |
def | findOnlineViewer |
def | findPlugin |
def | findPluginManager |
def | findPositionSensor |
def | findReceiver |
def | findSeqPlugin |
def | findSpeakServer |
def | findStabilizerPlugin |
def | findStateProvider |
def | findStereoVision |
def | findWalkPlugin |
template<class Array > |
void | getMatrix33FromRowMajorArray (Matrix33 &m33, const Array &a, size_t top=0) |
HRPMODEL_API
OpenHRP::ModelLoader_var | getModelLoader (CosNaming::NamingContext_var cxt) |
HRPMODEL_API
OpenHRP::ModelLoader_var | getModelLoader (CORBA_ORB_var orb) |
HRP_UTIL_EXPORT
OpenHRP::OnlineViewer_var | getOnlineViewer (int argc, char **argv) |
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 void | getPathFromUrl (string &refUrl, const string &rootDir, string srcUrl) |
def | getRootNamingContext |
template<class V > |
void | getVector3 (Vector3 &v3, const V &v, size_t top=0) |
template<class M > |
void | getVector3 (Vector3 &v3, const M &m, size_t row, size_t col) |
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 (const std::string pathString, BodyInterface *bodyInterface) |
HRPMODEL_API int | loadBodyCustomizers (const std::string pathString) |
HRPMODEL_API int | loadBodyCustomizers (BodyInterface *bodyInterface) |
HRPMODEL_API int | loadBodyCustomizers () |
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, int &argc, char *argv[]) |
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) |
def | loadVRML |
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, double &value) |
HRP_UTIL_EXPORT EasyScanner & | operator>> (EasyScanner &scanner, int &value) |
HRP_UTIL_EXPORT EasyScanner & | operator>> (EasyScanner &scanner, const char *matchString) |
HRP_UTIL_EXPORT EasyScanner & | operator>> (EasyScanner &scanner, char matchChar) |
HRP_UTIL_EXPORT EasyScanner & | operator>> (EasyScanner &scanner, std::string &str) |
HRP_UTIL_EXPORT EasyScanner & | operator>> (EasyScanner &scanner, EasyScanner::Endl endl) |
def | radians |
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, V &v, size_t top=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) |
int | solveLinearEquation (const dmatrix &_a, const dvector &_b, dvector &_x, double _sv_ratio) |
int | solveLinearEquationLU (dmatrix a, const dmatrix &b, dmatrix &out_x) |
int | solveLinearEquationLU (const dmatrix &_a, const dvector &_b, dvector &_x) |
int | solveLinearEquationSVD (const dmatrix &_a, const dvector &_b, dvector &_x, double _sv_ratio) |
Matrix33 | trans (const Matrix33 &m) |
def | unbindObject |
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 |
| rootnc = None |