21 #include <boost/bind.hpp>    22 #include <boost/format.hpp>    24 #include <hrpCorba/ViewSimulator.hh>    35 using namespace boost;
    38     typedef map<string, string> SensorTypeMap;
    39     SensorTypeMap sensorTypeMap;
    64     return CORBA::string_dup(
name_.c_str());
    70     return CORBA::string_dup(
url_.c_str());
    76     return new StringSequence(
info_);
    82     return new LinkInfoSequence(
links_);
   111     replace( url2, 
string(
"\\"), 
string(
"/") );
   113     url_ = CORBA::string_dup(url2.c_str());
   122         result = modelNodeSet.loadModelFile( filename );
   130         cout << ex.
what() << endl;
   131         cout << 
"Retrying to load the file as a standard VRML file" << endl;
   134             parser.
load(filename);
   137             LinkInfo &linfo = 
links_[0];
   138             linfo.name = CORBA::string_dup(
"root");
   139             linfo.parentIndex = -1;
   141             linfo.jointType = CORBA::string_dup(
"fixed");
   142             linfo.jointValue = 0;
   143             for (
int i=0; 
i<3; 
i++){
   144                 linfo.jointAxis[
i] = 0;
   145                 linfo.translation[
i] = 0;
   146                 linfo.rotation[
i] = 0;
   147                 linfo.centerOfMass[
i] = 0;
   149             linfo.jointAxis[2] = 1; 
   150             linfo.rotation[2] = 1; linfo.rotation[3] = 0;
   152             for (
int i=0; 
i<9; 
i++) linfo.inertia[
i] = 0;
   166             throw ModelLoader::ModelLoaderException(ex.
getFullMessage().c_str());
   171         throw ModelLoader::ModelLoaderException(
"The model file cannot be loaded.");
   174     const string& humanoidName = modelNodeSet.humanoidNode()->defName;
   175     name_ = humanoidName.c_str();
   176     const MFString& 
info = modelNodeSet.humanoidNode()->fields[
"info"].mfString();
   177     info_.length(info.size());
   178     for (
unsigned int i=0; 
i<
info_.length(); 
i++){
   179         info_[
i] = CORBA::string_dup(info[
i].c_str());
   182     int numJointNodes = modelNodeSet.numJointNodes();
   184     links_.length(numJointNodes);
   185     if( 0 < numJointNodes ) {
   186         int currentIndex = 0;
   192     for(
int i = 0 ; 
i < numJointNodes ; ++
i) {
   198     for(
int linkIndex = 0; linkIndex < numJointNodes ; ++linkIndex){
   200         coldetModel->setName(std::string(
links_[linkIndex].
name));
   202         int triangleIndex = 0;
   205         const TransformedShapeIndexSequence& shapeIndices = 
linkShapeIndices_[linkIndex];
   206         setColdetModel(coldetModel, shapeIndices, E, vertexIndex, triangleIndex);
   209         const SensorInfoSequence& sensors = 
links_[linkIndex].sensors;
   210         for (
unsigned int i=0; 
i<sensors.length(); 
i++){
   211             const SensorInfo& sensor = sensors[
i];
   213                                  sensor.rotation[2]), sensor.rotation[3]);
   214             T(0,3) = sensor.translation[0];
   215             T(1,3) = sensor.translation[1];
   216             T(2,3) = sensor.translation[2];
   217             const TransformedShapeIndexSequence& sensorShapeIndices = sensor.shapeIndices;
   218             setColdetModel(coldetModel, sensorShapeIndices, T, vertexIndex, triangleIndex);
   222             coldetModel->build();
   225         links_[linkIndex].AABBmaxDepth = coldetModel->getAABBTreeDepth();
   226         links_[linkIndex].AABBmaxNum = coldetModel->getAABBmaxNum();
   231         int n = modelNodeSet.numExtraJointNodes();
   233     for(
int i=0; 
i < 
n; ++
i){
   236         ExtraJointInfo_var extraJointInfo(
new ExtraJointInfo());
   237                 extraJointInfo->name =  CORBA::string_dup( modelNodeSet.extraJointNode(
i)->defName.c_str() );
   239         string link1Name, link2Name;
   242                 extraJointInfo->link[0] = CORBA::string_dup(link1Name.c_str());
   243                 extraJointInfo->link[1] = CORBA::string_dup(link2Name.c_str());
   247         if(jointType == 
"xy"){
   248                    extraJointInfo->jointType = EJ_XY;
   249         } 
else if(jointType == 
"xyz"){
   250            extraJointInfo->jointType = EJ_XYZ;
   251         } 
else if(jointType == 
"z"){
   252            extraJointInfo->jointType = EJ_Z;
   257                 copyVrmlField( f, 
"link1LocalPos", extraJointInfo->point[0] );
   258                 copyVrmlField( f, 
"link2LocalPos", extraJointInfo->point[1] );
   267     int index = currentIndex;
   270     LinkInfo_var linkInfo(
new LinkInfo());
   271     linkInfo->parentIndex = parentIndex;
   273     size_t numChildren = jointNodeSet->childJointNodeSets.size();
   275     for( 
size_t i = 0 ; 
i < numChildren ; ++
i ){
   279         long childIndicesLength = linkInfo->childIndices.length();
   280         linkInfo->childIndices.length( childIndicesLength + 1 );
   281         linkInfo->childIndices[childIndicesLength] = childIndex;
   286         vector<VrmlProtoInstancePtr>& segmentNodes = jointNodeSet->segmentNodes;
   287         int numSegment = segmentNodes.size();
   288         links_[index].segments.length(numSegment);
   289         for(
int i = 0 ; 
i < numSegment ; ++
i){
   290             SegmentInfo_var segmentInfo(
new SegmentInfo());
   291             Matrix44 T = jointNodeSet->transforms.at(
i);
   292             long s = 
links_[index].shapeIndices.length();
   295                 for(
int col=0; col < 4; ++col){
   296                     segmentInfo->transformMatrix[p++] = T(
row, col);
   300             long e =
links_[index].shapeIndices.length();
   301             segmentInfo->shapeIndices.length(e-s);
   302             for(
int j=0, k=s; k<e; k++)
   303                 segmentInfo->shapeIndices[
j++] = k;
   304             links_[index].segments[
i] = segmentInfo;
   312     catch( ModelLoader::ModelLoaderException& ex ) {
   313         string name(linkInfo->name);
   314         string error = name.empty() ? 
"Unnamed JointNode" : 
name;
   316         error += ex.description;
   317         throw ModelLoader::ModelLoaderException( error.c_str() );
   326     LinkInfo& linkInfo = 
links_[linkInfoIndex];
   328     linkInfo.name =  CORBA::string_dup( jointNode->defName.c_str() );
   334     linkInfo.jointId = (CORBA::Short)jointId; 
   336     linkInfo.jointAxis[0] = 0.0;
   337     linkInfo.jointAxis[1] = 0.0;
   338     linkInfo.jointAxis[2] = 0.0;
   342     switch( fJointAxis.
typeId() ) {
   347             if( axisLabel == 
"X" )              { linkInfo.jointAxis[0] = 1.0; }
   348             else if( axisLabel == 
"Y" ) { linkInfo.jointAxis[1] = 1.0; }
   349             else if( axisLabel == 
"Z" ) { linkInfo.jointAxis[2] = 1.0; }
   361     std::string jointType;
   363     linkInfo.jointType = CORBA::string_dup( jointType.c_str() );
   377         linkInfo.climit.length((CORBA::ULong)0); 
   381     copyVrmlField( fmap, 
"rotorInertia",  linkInfo.rotorInertia );
   382     copyVrmlField( fmap, 
"rotorResistor", linkInfo.rotorResistor );
   384     copyVrmlField( fmap, 
"encoderPulse",  linkInfo.encoderPulse );
   390     LinkInfo& linkInfo = 
links_[linkInfoIndex];
   392     vector<VrmlProtoInstancePtr>& segmentNodes = jointNodeSet->segmentNodes;
   393     int numSegment = segmentNodes.size();
   396     for( 
int i = 0 ; 
i < 3 ; ++
i ) {
   397         linkInfo.centerOfMass[
i] = 0.0;
   398         for( 
int j = 0 ; 
j < 3 ; ++
j ) {
   399             linkInfo.inertia[
i*3 + 
j] = 0.0;
   409     std::vector<Vector4, Eigen::aligned_allocator<Vector4> > centerOfMassArray;
   410     std::vector<double> massArray;
   411     for(
int i = 0 ; 
i < numSegment ; ++
i){
   412         SegmentInfo& segmentInfo = linkInfo.segments[
i];
   413         Matrix44 T = jointNodeSet->transforms.at(
i);
   414         DblArray3& centerOfMass = segmentInfo.centerOfMass;
   415         CORBA::Double& mass =segmentInfo.mass;
   416         DblArray9& inertia = segmentInfo.inertia;
   421         Vector4 c0(centerOfMass[0], centerOfMass[1], centerOfMass[2], 1.0);
   423         centerOfMassArray.push_back(c1);
   424         massArray.push_back(mass);
   425         for(
int j=0; 
j<3; 
j++){
   426             linkInfo.centerOfMass[
j] = c1(
j) * mass + linkInfo.centerOfMass[
j] * linkInfo.mass;
   428         linkInfo.mass += mass;
   429         if(linkInfo.mass > 0.0){
   430             for(
int j=0; 
j<3; 
j++){
   431                 linkInfo.centerOfMass[
j] /= linkInfo.mass;
   435         I << inertia[0], inertia[1], inertia[2], inertia[3], inertia[4], inertia[5], inertia[6], inertia[7], inertia[8];
   437         R << T(0,0), T(0,1), T(0,2), T(1,0), T(1,1), T(1,2), T(2,0), T(2,1), T(2,2);
   439         for(
int j=0; 
j<3; 
j++){
   440             for(
int k=0; k<3; k++)
   441                 linkInfo.inertia[
j*3+k] += I1(
j,k);    
   443         segmentInfo.name = CORBA::string_dup( segmentNodes[
i]->defName.c_str() );
   445     if(linkInfo.mass <=0.0 )
   446         std::cerr << 
"Warning: Mass is zero. <Model>" << 
name_ << 
" <Link>" << linkInfo.name << std::endl;
   448     for(
int i = 0 ; 
i < numSegment ; ++
i){
   450         double x = 
c(0) - linkInfo.centerOfMass[0];
   451         double y = 
c(1) - linkInfo.centerOfMass[1];
   452         double z = 
c(2) - linkInfo.centerOfMass[2];
   453         double m = massArray.at(
i);
   455         linkInfo.inertia[0] += m * (y*y + z*z);
   456         linkInfo.inertia[1] += -m * x * 
y;
   457         linkInfo.inertia[2] += -m * x * z;
   458         linkInfo.inertia[3] += -m * y * 
x;
   459         linkInfo.inertia[4] += m * (z*z + x*
x);
   460         linkInfo.inertia[5] += -m * y * z;
   461         linkInfo.inertia[6] += -m * z * 
x;
   462         linkInfo.inertia[7] += -m * z * 
y;
   463         linkInfo.inertia[8] += m * (x*x + y*
y);
   470     LinkInfo& linkInfo = 
links_[linkInfoIndex];
   472     vector<VrmlProtoInstancePtr>& sensorNodes = jointNodeSet->sensorNodes;
   474     int numSensors = sensorNodes.size();
   475     linkInfo.sensors.length(numSensors);
   477     for(
int i = 0 ; 
i < numSensors ; ++
i) {
   478         SensorInfo_var sensorInfo( 
new SensorInfo() );
   480         linkInfo.sensors[
i] = sensorInfo;
   487     LinkInfo& linkInfo = 
links_[linkInfoIndex];
   489     vector<VrmlProtoInstancePtr>& hwcNodes = jointNodeSet->hwcNodes;
   491     int numHwcs = hwcNodes.size();
   492     linkInfo.hwcs.length(numHwcs);
   494     for(
int i = 0 ; 
i < numHwcs ; ++
i) {
   495         HwcInfo_var hwcInfo( 
new HwcInfo() );
   497         linkInfo.hwcs[
i] = hwcInfo;
   503     LinkInfo& linkInfo = 
links_[linkInfoIndex];
   505     vector<pair<Matrix44, VrmlNodePtr>,
   506            Eigen::aligned_allocator<pair<Matrix44, VrmlNodePtr> > >& lightNodes = jointNodeSet->lightNodes;
   508     int numLights = lightNodes.size();
   509     linkInfo.lights.length(numLights);
   511     for(
int i = 0 ; 
i < numLights ; ++
i) {
   512         LightInfo_var lightInfo( 
new LightInfo() );
   514         linkInfo.lights[
i] = lightInfo;
   521     if(sensorTypeMap.empty()) {
   522         sensorTypeMap[
"ForceSensor"]        = 
"Force";
   523         sensorTypeMap[
"Gyro"]               = 
"RateGyro";
   524         sensorTypeMap[
"AccelerationSensor"] = 
"Acceleration";
   525         sensorTypeMap[
"PressureSensor"]     = 
"";
   526         sensorTypeMap[
"PhotoInterrupter"]   = 
"";
   527         sensorTypeMap[
"VisionSensor"]       = 
"Vision";
   528         sensorTypeMap[
"TorqueSensor"]       = 
"";
   529         sensorTypeMap[
"RangeSensor"]        = 
"Range";
   533         sensorInfo.name = CORBA::string_dup( sensorNode->defName.c_str() );
   541         SensorTypeMap::iterator p = sensorTypeMap.find( sensorNode->proto->protoName );
   542         std::string sensorType;
   543         if(p != sensorTypeMap.end()){
   544             sensorType = p->second;
   545             sensorInfo.type = CORBA::string_dup( sensorType.c_str() );
   547             throw ModelLoader::ModelLoaderException(
"Unknown Sensor Node");
   550         if(sensorType == 
"Force") {
   551             sensorInfo.specValues.length( CORBA::ULong(6) );
   552             DblArray3 maxForce, maxTorque;
   555             sensorInfo.specValues[0] = maxForce[0];
   556             sensorInfo.specValues[1] = maxForce[1];
   557             sensorInfo.specValues[2] = maxForce[2];
   558             sensorInfo.specValues[3] = maxTorque[0];
   559             sensorInfo.specValues[4] = maxTorque[1];
   560             sensorInfo.specValues[5] = maxTorque[2];
   562         } 
else if(sensorType == 
"RateGyro") {
   563             sensorInfo.specValues.length( CORBA::ULong(3) );
   564             DblArray3 maxAngularVelocity;
   565             copyVrmlField(fmap, 
"maxAngularVelocity", maxAngularVelocity);
   566             sensorInfo.specValues[0] = maxAngularVelocity[0];
   567             sensorInfo.specValues[1] = maxAngularVelocity[1];
   568             sensorInfo.specValues[2] = maxAngularVelocity[2];
   570         } 
else if( sensorType == 
"Acceleration" ){
   571             sensorInfo.specValues.length( CORBA::ULong(3) );
   572             DblArray3 maxAcceleration;
   574             sensorInfo.specValues[0] = maxAcceleration[0];
   575             sensorInfo.specValues[1] = maxAcceleration[1];
   576             sensorInfo.specValues[2] = maxAcceleration[2];
   578         } 
else if( sensorType == 
"Vision" ){
   579             sensorInfo.specValues.length( CORBA::ULong(7) );
   581             CORBA::Double specValues[3];
   585             sensorInfo.specValues[0] = specValues[0];
   586             sensorInfo.specValues[1] = specValues[1];
   587             sensorInfo.specValues[2] = specValues[2];
   589             std::string sensorTypeString;
   592             if(sensorTypeString==
"NONE" ) {
   593                 sensorInfo.specValues[3] = Camera::NONE;
   594             } 
else if(sensorTypeString==
"COLOR") {
   595                 sensorInfo.specValues[3] = Camera::COLOR;
   596             } 
else if(sensorTypeString==
"MONO") {
   597                 sensorInfo.specValues[3] = Camera::MONO;
   598             } 
else if(sensorTypeString==
"DEPTH") {
   599                 sensorInfo.specValues[3] = Camera::DEPTH;
   600             } 
else if(sensorTypeString==
"COLOR_DEPTH") {
   601                 sensorInfo.specValues[3] = Camera::COLOR_DEPTH;
   602             } 
else if(sensorTypeString==
"MONO_DEPTH") {
   603                 sensorInfo.specValues[3] = Camera::MONO_DEPTH;
   605                 throw ModelLoader::ModelLoaderException(
"Sensor node has unkown type string");
   612             sensorInfo.specValues[4] = 
static_cast<CORBA::Double
>(
width);
   613             sensorInfo.specValues[5] = 
static_cast<CORBA::Double
>(
height);
   617             sensorInfo.specValues[6] = frameRate;
   618         } 
else if( sensorType == 
"Range" ){
   619             sensorInfo.specValues.length( CORBA::ULong(4) );
   622             sensorInfo.specValues[0] = v;
   624             sensorInfo.specValues[1] = v;
   626             sensorInfo.specValues[2] = v;
   628             sensorInfo.specValues[3] = v;
   644             for (
unsigned int i=0; 
i<children.size(); 
i++){
   646                                    sensorInfo.shapeIndices, sensorInfo.inlinedShapeTransformMatrices, &
topUrl());
   649     } 
catch(ModelLoader::ModelLoaderException& ex) {
   652         error += ex.description;
   653         throw ModelLoader::ModelLoaderException( error.c_str() );
   660         hwcInfo.name = CORBA::string_dup( hwcNode->defName.c_str() );
   669         hwcInfo.url = CORBA::string_dup( url.c_str() );
   675             for (
unsigned int i=0; 
i<children.size(); 
i++){
   677                                    hwcInfo.shapeIndices, hwcInfo.inlinedShapeTransformMatrices, &
topUrl());
   680     } 
catch(ModelLoader::ModelLoaderException& ex) {
   681         throw ModelLoader::ModelLoaderException( ex.description );
   686                                   std::pair<Matrix44, VrmlNodePtr> &transformedLight )
   688     VrmlNode *lightNode = transformedLight.second.get();
   689     Matrix44 &T = transformedLight.first;
   690     for (
int i=0; 
i<3; 
i++){
   691         for (
int j=0; 
j<4; 
j++){
   692             lightInfo.transformMatrix[
i*4+
j] =  T(
i,
j);
   696         lightInfo.name = CORBA::string_dup( lightNode->
defName.c_str() );
   701             lightInfo.type = OpenHRP::POINT;
   703             lightInfo.intensity = plight->intensity;
   704             lightInfo.on = plight->on;
   705             lightInfo.radius = plight->radius;
   706             for (
int i=0; 
i<3; 
i++){
   707                 lightInfo.attenuation[
i] = plight->attenuation[
i];
   708                 lightInfo.color[
i] = plight->color[
i];
   709                 lightInfo.location[
i] = plight->location[
i];
   712             lightInfo.type = OpenHRP::DIRECTIONAL;
   715             lightInfo.on = dlight->
on;
   716             for (
int i=0; 
i<3; 
i++){
   717                 lightInfo.color[
i] = dlight->
color[
i];
   721             lightInfo.type = OpenHRP::SPOT;
   724             lightInfo.on = slight->
on;
   725             lightInfo.radius = slight->
radius;
   728             for (
int i=0; 
i<3; 
i++){
   730                 lightInfo.color[
i] = slight->
color[
i];
   735             throw ModelLoader::ModelLoaderException(
"unknown light type");
   737     } 
catch(ModelLoader::ModelLoaderException& ex) {
   738         throw ModelLoader::ModelLoaderException( ex.description );
   743     if(param == 
"readImage")
   754     if(param == 
"readImage")
   761     if(param == 
"AABBType")
   768     const double EPS = 1.0e-6;
   770     std::vector<Vector3> boxSizeMap;
   771     std::vector<Vector3> boundingBoxData;
   773     for(
unsigned int i=0; 
i<
links_.length(); 
i++){
   778             _depth = inputData[
i];
   779         if( _depth >= 
links_[i].AABBmaxDepth)
   780             _depth = 
links_[
i].AABBmaxDepth-1;
   783             std::vector<TransformedShapeIndex> tsiMap;
   784             links_[
i].shapeIndices.length(0);
   785             SensorInfoSequence& sensors = 
links_[
i].sensors;
   786             for (
unsigned int j=0; 
j<sensors.length(); 
j++){
   787                 SensorInfo& sensor = sensors[
j];
   788                 sensor.shapeIndices.length(0);
   791             for(
unsigned int j=0; 
j<boundingBoxData.size()/2; 
j++){
   795                 for( ; k<boxSizeMap.size(); k++)
   796                     if((boxSizeMap[k] - boundingBoxData[
j*2+1]).norm() < 
EPS)
   798                 if( k<boxSizeMap.size() )
   801                     boxSizeMap.push_back(boundingBoxData[
j*2+1]);
   807                     for( ; l<tsiMap.size(); l++){
   808                         Vector3 p(tsiMap[l].transformMatrix[3],tsiMap[l].transformMatrix[7],tsiMap[l].transformMatrix[11]);
   809                         if((p - boundingBoxData[
j*2]).
norm() < EPS && tsiMap[l].shapeIndex == (
int)k)
   812                     if( l==tsiMap.size() )
   818                     links_[
i].shapeIndices.length(num+1);
   819                     TransformedShapeIndex& tsi = 
links_[
i].shapeIndices[
num];
   820                     tsi.inlinedShapeTransformMatrixIndex = -1;
   824                        for(
int col=0; col < 4; ++col)
   828                                         tsi.transformMatrix[p++] = boundingBoxData[
j*2][0];
   831                                         tsi.transformMatrix[p++] = boundingBoxData[
j*2][1];
   834                                         tsi.transformMatrix[p++] = boundingBoxData[
j*2][2];
   840                                 tsi.transformMatrix[p++] = T(
row, col);
   842                     tsiMap.push_back(tsi);
   852     for(
size_t i = 0 ; 
i < 
links_.length() ; ++
i) {
 
std::vector< SFNode > MFNode
void setParam(std::string param, bool value)
bool getParam(std::string param)
AllLinkShapeIndexSequence linkShapeIndices_
std::string & replace(std::string &str, const std::string &sb, const std::string &sa)
void setBoundingBoxData(const Vector3 &boxSize, int shapeIndex)
BodyInfo_impl(PortableServer::POA_ptr poa)
Modifications controlling boost library behavior. 
Abstract base class of all vrml nodes. 
OpenHRP::ModelLoader::AABBdataType AABBdataType_
void changetoOriginData()
virtual LinkInfoSequence * links()
std::map< std::string, VrmlVariantField > TProtoFieldMap
boost::intrusive_ptr< VrmlProtoInstance > VrmlProtoInstancePtr
void readLightNode(int linkInfoIndex, LightInfo &LightInfo, std::pair< Matrix44, VrmlNodePtr > &transformedLight)
void error(char *msg) const
void createAppearanceInfo()
void readSensorNode(int linkInfoIndex, SensorInfo &sensorInfo, VrmlProtoInstancePtr sensorNode)
virtual const std::string & topUrl()
void applyTriangleMeshShaper(VrmlNodePtr node)
AllLinkShapeIndexSequence originlinkShapeIndices_
void changetoBoundingBox(unsigned int *depth)
png_infop png_uint_32 * width
void copyVrmlField(TProtoFieldMap &fmap, const std::string &name, std::string &out_s)
png_infop png_uint_32 png_uint_32 * height
def j(str, encoding="cp932")
void loadModelFile(const std::string &filename)
This function loads a model file and creates a BodyInfo object. 
void load(const std::string &filename)
void setHwcs(int linkInfoIndex, JointNodeSetPtr jointNodeSet)
Header file of Image Converter class. 
void setSegmentParameters(int linkInfoIndex, JointNodeSetPtr jointNodeSet)
std::vector< ColdetModelPtr > linkColdetModels
void copyVrmlRotationFieldToDblArray4(TProtoFieldMap &fieldMap, const std::string name, DblArray4 &out_R)
ExtraJointInfoSequence extraJoints_
boost::intrusive_ptr< VrmlNode > VrmlNodePtr
void setColdetModel(ColdetModelPtr &coldetModel, TransformedShapeIndexSequence shapeIndices, const Matrix44 &Tparent, int &vertexIndex, int &triangleIndex)
HRP_UTIL_EXPORT string deleteURLScheme(string url)
void setJointParameters(int linkInfoIndex, VrmlProtoInstancePtr jointNode)
std::string getFullMessage()
void setSensors(int linkInfoIndex, JointNodeSetPtr jointNodeSet)
Parser for VRML97 format. 
virtual StringSequence * info()
void readHwcNode(int linkInfoIndex, HwcInfo &hwcInfo, VrmlProtoInstancePtr hwcNode)
std::vector< SFString > MFString
virtual AllLinkShapeIndexSequence * linkShapeIndices()
int readJointNodeSet(JointNodeSetPtr jointNodeSet, int ¤tIndex, int motherIndex)
HRP_UTIL_EXPORT void calcRodrigues(Matrix33 &out_R, const Vector3 &axis, double q)
static void putMessage(const std::string &message)
virtual ExtraJointInfoSequence * extraJoints()
boost::shared_ptr< JointNodeSet > JointNodeSetPtr
void traverseShapeNodes(VrmlNode *node, const Matrix44 &T, TransformedShapeIndexSequence &io_shapeIndices, DblArray12Sequence &inlinedShapeM, const SFString *url=NULL)
const char * what() const 
boost::intrusive_ptr< ColdetModel > ColdetModelPtr
void restoreOriginalData()
void setLights(int linkInfoIndex, JointNodeSetPtr jointNodeSet)
boost::signal< void(const std::string &message)> sigMessage
The header file of a text scanner class.