Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
@@ -110,6 +110,8 @@ typedef struct bInvalidHandle {
|
|||||||
class btMultiBodyLinkFloatData;
|
class btMultiBodyLinkFloatData;
|
||||||
class btMultiBodyDoubleData;
|
class btMultiBodyDoubleData;
|
||||||
class btMultiBodyFloatData;
|
class btMultiBodyFloatData;
|
||||||
|
class btMultiBodyLinkColliderFloatData;
|
||||||
|
class btMultiBodyLinkColliderDoubleData;
|
||||||
// -------------------------------------------------- //
|
// -------------------------------------------------- //
|
||||||
class PointerArray
|
class PointerArray
|
||||||
{
|
{
|
||||||
@@ -1440,5 +1442,27 @@ typedef struct bInvalidHandle {
|
|||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
// -------------------------------------------------- //
|
||||||
|
class btMultiBodyLinkColliderFloatData
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
btCollisionObjectFloatData m_colObjData;
|
||||||
|
void *m_multiBody;
|
||||||
|
int m_link;
|
||||||
|
char m_padding[4];
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
// -------------------------------------------------- //
|
||||||
|
class btMultiBodyLinkColliderDoubleData
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
btCollisionObjectDoubleData m_colObjData;
|
||||||
|
void *m_multiBody;
|
||||||
|
int m_link;
|
||||||
|
char m_padding[4];
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
#endif//__BULLET_H__
|
#endif//__BULLET_H__
|
||||||
@@ -181,6 +181,11 @@ void btBulletFile::parseData()
|
|||||||
m_multiBodies.push_back((bStructHandle*)id);
|
m_multiBodies.push_back((bStructHandle*)id);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (dataChunk.code == BT_MB_LINKCOLLIDER_CODE)
|
||||||
|
{
|
||||||
|
m_multiBodyLinkColliders.push_back((bStructHandle*)id);
|
||||||
|
}
|
||||||
|
|
||||||
if (dataChunk.code == BT_SOFTBODY_CODE)
|
if (dataChunk.code == BT_SOFTBODY_CODE)
|
||||||
{
|
{
|
||||||
m_softBodies.push_back((bStructHandle*) id);
|
m_softBodies.push_back((bStructHandle*) id);
|
||||||
|
|||||||
@@ -41,6 +41,8 @@ namespace bParse {
|
|||||||
|
|
||||||
btAlignedObjectArray<bStructHandle*> m_multiBodies;
|
btAlignedObjectArray<bStructHandle*> m_multiBodies;
|
||||||
|
|
||||||
|
btAlignedObjectArray<bStructHandle*> m_multiBodyLinkColliders;
|
||||||
|
|
||||||
btAlignedObjectArray<bStructHandle*> m_softBodies;
|
btAlignedObjectArray<bStructHandle*> m_softBodies;
|
||||||
|
|
||||||
btAlignedObjectArray<bStructHandle*> m_rigidBodies;
|
btAlignedObjectArray<bStructHandle*> m_rigidBodies;
|
||||||
|
|||||||
@@ -5,6 +5,7 @@ INCLUDE_DIRECTORIES(
|
|||||||
|
|
||||||
ADD_LIBRARY(
|
ADD_LIBRARY(
|
||||||
BulletWorldImporter
|
BulletWorldImporter
|
||||||
|
btMultiBodyWorldImporter.cpp
|
||||||
btBulletWorldImporter.cpp
|
btBulletWorldImporter.cpp
|
||||||
btBulletWorldImporter.h
|
btBulletWorldImporter.h
|
||||||
btWorldImporter.cpp
|
btWorldImporter.cpp
|
||||||
|
|||||||
@@ -0,0 +1,204 @@
|
|||||||
|
#include "btMultiBodyWorldImporter.h"
|
||||||
|
|
||||||
|
#include "LinearMath/btSerializer.h"
|
||||||
|
#include "../BulletFileLoader/btBulletFile.h"
|
||||||
|
#include "btBulletWorldImporter.h"
|
||||||
|
#include "btBulletDynamicsCommon.h"
|
||||||
|
#include "BulletDynamics/Featherstone/btMultiBody.h"
|
||||||
|
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
||||||
|
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
||||||
|
|
||||||
|
struct btMultiBodyWorldImporterInternalData
|
||||||
|
{
|
||||||
|
btMultiBodyDynamicsWorld* m_mbDynamicsWorld;
|
||||||
|
btHashMap<btHashPtr, btMultiBody*> m_mbMap;
|
||||||
|
};
|
||||||
|
|
||||||
|
btMultiBodyWorldImporter::btMultiBodyWorldImporter(btMultiBodyDynamicsWorld* world)
|
||||||
|
:btBulletWorldImporter(world)
|
||||||
|
{
|
||||||
|
m_data = new btMultiBodyWorldImporterInternalData;
|
||||||
|
m_data->m_mbDynamicsWorld = world;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
btMultiBodyWorldImporter::~btMultiBodyWorldImporter()
|
||||||
|
{
|
||||||
|
delete m_data;
|
||||||
|
}
|
||||||
|
|
||||||
|
void btMultiBodyWorldImporter::deleteAllData()
|
||||||
|
{
|
||||||
|
btBulletWorldImporter::deleteAllData();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile2)
|
||||||
|
{
|
||||||
|
bool result = btBulletWorldImporter::convertAllObjects(bulletFile2);
|
||||||
|
|
||||||
|
|
||||||
|
//convert all multibodies
|
||||||
|
for (int i=0;i<bulletFile2->m_multiBodies.size();i++)
|
||||||
|
{
|
||||||
|
|
||||||
|
if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
|
||||||
|
{
|
||||||
|
btMultiBodyDoubleData* mbd = (btMultiBodyDoubleData*) bulletFile2->m_multiBodies[i];
|
||||||
|
bool isFixedBase = mbd->m_baseMass==0;
|
||||||
|
bool canSleep = false;
|
||||||
|
btVector3 baseInertia;
|
||||||
|
baseInertia.deSerializeDouble(mbd->m_baseInertia);
|
||||||
|
btMultiBody* mb = new btMultiBody(mbd->m_numLinks,mbd->m_baseMass,baseInertia,isFixedBase,canSleep);
|
||||||
|
mb->setHasSelfCollision(false);
|
||||||
|
|
||||||
|
m_data->m_mbMap.insert(mbd,mb);
|
||||||
|
for (int i=0;i<mbd->m_numLinks;i++)
|
||||||
|
{
|
||||||
|
btVector3 localInertiaDiagonal;
|
||||||
|
localInertiaDiagonal.deSerializeDouble(mbd->m_links[i].m_linkInertia);
|
||||||
|
btQuaternion parentRotToThis;
|
||||||
|
parentRotToThis.deSerializeDouble(mbd->m_links[i].m_zeroRotParentToThis);
|
||||||
|
btVector3 parentComToThisPivotOffset;
|
||||||
|
parentComToThisPivotOffset.deSerializeDouble(mbd->m_links[i].m_parentComToThisComOffset);
|
||||||
|
btVector3 thisPivotToThisComOffset;
|
||||||
|
thisPivotToThisComOffset.deSerializeDouble(mbd->m_links[i].m_thisPivotToThisComOffset);
|
||||||
|
|
||||||
|
switch (mbd->m_links[i].m_jointType)
|
||||||
|
{
|
||||||
|
case btMultibodyLink::eFixed:
|
||||||
|
{
|
||||||
|
|
||||||
|
|
||||||
|
mb->setupFixed(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
|
||||||
|
parentRotToThis, parentComToThisPivotOffset,thisPivotToThisComOffset);
|
||||||
|
//search for the collider
|
||||||
|
//mbd->m_links[i].m_linkCollider
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case btMultibodyLink::ePrismatic:
|
||||||
|
{
|
||||||
|
btVector3 jointAxis;
|
||||||
|
jointAxis.deSerializeDouble(mbd->m_links[i].m_jointAxisBottom[0]);
|
||||||
|
bool disableParentCollision = true;//todo
|
||||||
|
mb->setupPrismatic(i,mbd->m_links[i].m_linkMass,localInertiaDiagonal,mbd->m_links[i].m_parentIndex,
|
||||||
|
parentRotToThis,jointAxis, parentComToThisPivotOffset,thisPivotToThisComOffset,disableParentCollision);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case btMultibodyLink::eRevolute:
|
||||||
|
{
|
||||||
|
btVector3 jointAxis;
|
||||||
|
jointAxis.deSerializeDouble(mbd->m_links[i].m_jointAxisTop[0]);
|
||||||
|
bool disableParentCollision = true;//todo
|
||||||
|
mb->setupRevolute(i,mbd->m_links[i].m_linkMass,localInertiaDiagonal,mbd->m_links[i].m_parentIndex,
|
||||||
|
parentRotToThis, jointAxis,parentComToThisPivotOffset,thisPivotToThisComOffset,disableParentCollision);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case btMultibodyLink::eSpherical:
|
||||||
|
{
|
||||||
|
btAssert(0);
|
||||||
|
bool disableParentCollision = true;//todo
|
||||||
|
mb->setupSpherical(i,mbd->m_links[i].m_linkMass,localInertiaDiagonal,mbd->m_links[i].m_parentIndex,
|
||||||
|
parentRotToThis,parentComToThisPivotOffset,thisPivotToThisComOffset,disableParentCollision);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case btMultibodyLink::ePlanar:
|
||||||
|
{
|
||||||
|
btAssert(0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
{
|
||||||
|
btAssert(0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//convert all multibody link colliders
|
||||||
|
for (int i=0;i<bulletFile2->m_multiBodyLinkColliders.size();i++)
|
||||||
|
{
|
||||||
|
if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
|
||||||
|
{
|
||||||
|
btMultiBodyLinkColliderDoubleData* mblcd = (btMultiBodyLinkColliderDoubleData*) bulletFile2->m_multiBodyLinkColliders[i];
|
||||||
|
|
||||||
|
btMultiBody** ptr = m_data->m_mbMap[mblcd->m_multiBody];
|
||||||
|
if (ptr)
|
||||||
|
{
|
||||||
|
btMultiBody* multiBody = *ptr;
|
||||||
|
|
||||||
|
|
||||||
|
btCollisionShape** shapePtr = m_shapeMap.find(mblcd->m_colObjData.m_collisionShape);
|
||||||
|
if (shapePtr && *shapePtr)
|
||||||
|
{
|
||||||
|
btTransform startTransform;
|
||||||
|
mblcd->m_colObjData.m_worldTransform.m_origin.m_floats[3] = 0.f;
|
||||||
|
startTransform.deSerializeDouble(mblcd->m_colObjData.m_worldTransform);
|
||||||
|
|
||||||
|
btCollisionShape* shape = (btCollisionShape*)*shapePtr;
|
||||||
|
if (shape)
|
||||||
|
{
|
||||||
|
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(multiBody, mblcd->m_link);
|
||||||
|
col->setCollisionShape( shape );
|
||||||
|
|
||||||
|
//btCollisionObject* body = createCollisionObject(startTransform,shape,mblcd->m_colObjData.m_name);
|
||||||
|
col->setFriction(btScalar(mblcd->m_colObjData.m_friction));
|
||||||
|
col->setRestitution(btScalar(mblcd->m_colObjData.m_restitution));
|
||||||
|
//m_bodyMap.insert(colObjData,body);
|
||||||
|
if (mblcd->m_link==-1)
|
||||||
|
{
|
||||||
|
multiBody->setBaseCollider(col);
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
multiBody->getLink(mblcd->m_link).m_collider = col;
|
||||||
|
}
|
||||||
|
int mbLinkIndex = mblcd->m_link;
|
||||||
|
|
||||||
|
bool isDynamic = (mbLinkIndex<0 && multiBody->hasFixedBase())? false : true;
|
||||||
|
int collisionFilterGroup = isDynamic? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
|
||||||
|
int collisionFilterMask = isDynamic? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||||
|
|
||||||
|
#if 0
|
||||||
|
int colGroup=0, colMask=0;
|
||||||
|
int collisionFlags = mblcd->m_colObjData.m_collisionFlags;
|
||||||
|
if (collisionFlags & URDF_HAS_COLLISION_GROUP)
|
||||||
|
{
|
||||||
|
collisionFilterGroup = colGroup;
|
||||||
|
}
|
||||||
|
if (collisionFlags & URDF_HAS_COLLISION_MASK)
|
||||||
|
{
|
||||||
|
collisionFilterMask = colMask;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
m_data->m_mbDynamicsWorld->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);
|
||||||
|
}
|
||||||
|
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
printf("error: no shape found\n");
|
||||||
|
}
|
||||||
|
#if 0
|
||||||
|
//base and fixed? -> static, otherwise flag as dynamic
|
||||||
|
|
||||||
|
world1->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int i=0;i<m_data->m_mbMap.size();i++)
|
||||||
|
{
|
||||||
|
btMultiBody**ptr = m_data->m_mbMap.getAtIndex(i);
|
||||||
|
if (ptr)
|
||||||
|
{
|
||||||
|
btMultiBody* mb = *ptr;
|
||||||
|
mb->finalizeMultiDof();
|
||||||
|
|
||||||
|
m_data->m_mbDynamicsWorld->addMultiBody(mb);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return result;
|
||||||
|
}
|
||||||
@@ -0,0 +1,20 @@
|
|||||||
|
#ifndef BT_MULTIBODY_WORLD_IMPORTER_H
|
||||||
|
#define BT_MULTIBODY_WORLD_IMPORTER_H
|
||||||
|
|
||||||
|
#include "../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h"
|
||||||
|
|
||||||
|
class btMultiBodyWorldImporter : public btBulletWorldImporter
|
||||||
|
{
|
||||||
|
struct btMultiBodyWorldImporterInternalData* m_data;
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
btMultiBodyWorldImporter(class btMultiBodyDynamicsWorld* world);
|
||||||
|
virtual ~btMultiBodyWorldImporter();
|
||||||
|
|
||||||
|
virtual bool convertAllObjects( bParse::btBulletFile* bulletFile2);
|
||||||
|
|
||||||
|
virtual void deleteAllData();
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif //BT_MULTIBODY_WORLD_IMPORTER_H
|
||||||
@@ -149,6 +149,7 @@ typedef unsigned __int64 uint64_t;
|
|||||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||||
#include "BulletSoftBody/btSoftBodyData.h"
|
#include "BulletSoftBody/btSoftBodyData.h"
|
||||||
#include "BulletDynamics/Featherstone/btMultiBody.h"
|
#include "BulletDynamics/Featherstone/btMultiBody.h"
|
||||||
|
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
||||||
|
|
||||||
#ifdef HAVE_CONFIG_H
|
#ifdef HAVE_CONFIG_H
|
||||||
#include <config.h>
|
#include <config.h>
|
||||||
@@ -198,6 +199,7 @@ char *includefiles[] = {
|
|||||||
|
|
||||||
"../../../src/BulletSoftBody/btSoftBodyData.h",
|
"../../../src/BulletSoftBody/btSoftBodyData.h",
|
||||||
"../../../src/BulletDynamics/Featherstone/btMultiBody.h",
|
"../../../src/BulletDynamics/Featherstone/btMultiBody.h",
|
||||||
|
"../../../src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h",
|
||||||
// empty string to indicate end of includefiles
|
// empty string to indicate end of includefiles
|
||||||
""
|
""
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -284,9 +284,7 @@ end
|
|||||||
_OPTIONS["glfw_lib_name"] = default_glfw_lib_name
|
_OPTIONS["glfw_lib_name"] = default_glfw_lib_name
|
||||||
end
|
end
|
||||||
|
|
||||||
if (_OPTIONS["enable_static_vr_plugin"]) then
|
|
||||||
defines("STATIC_LINK_VR_PLUGIN")
|
|
||||||
end
|
|
||||||
|
|
||||||
newoption
|
newoption
|
||||||
{
|
{
|
||||||
|
|||||||
30
data/sphere_small_zeroinertia.urdf
Normal file
30
data/sphere_small_zeroinertia.urdf
Normal file
@@ -0,0 +1,30 @@
|
|||||||
|
<?xml version="0.0" ?>
|
||||||
|
<robot name="urdf_robot">
|
||||||
|
<link name="base_link">
|
||||||
|
<contact>
|
||||||
|
<rolling_friction value="0.001"/>
|
||||||
|
<spinning_friction value="0.001"/>
|
||||||
|
</contact>
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<mass value=".1"/>
|
||||||
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="textured_sphere_smooth.obj" scale="0.03 0.03 0.03"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="1 1 1 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.03"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
</robot>
|
||||||
|
|
||||||
@@ -4,7 +4,7 @@
|
|||||||
struct Common2dCanvasInterface
|
struct Common2dCanvasInterface
|
||||||
{
|
{
|
||||||
virtual ~Common2dCanvasInterface() {}
|
virtual ~Common2dCanvasInterface() {}
|
||||||
virtual int createCanvas(const char* canvasName, int width, int height)=0;
|
virtual int createCanvas(const char* canvasName, int width, int height, int xPos, int yPos)=0;
|
||||||
virtual void destroyCanvas(int canvasId)=0;
|
virtual void destroyCanvas(int canvasId)=0;
|
||||||
virtual void setPixel(int canvasId, int x, int y, unsigned char red, unsigned char green,unsigned char blue, unsigned char alpha)=0;
|
virtual void setPixel(int canvasId, int x, int y, unsigned char red, unsigned char green,unsigned char blue, unsigned char alpha)=0;
|
||||||
virtual void getPixel(int canvasId, int x, int y, unsigned char& red, unsigned char& green,unsigned char& blue, unsigned char& alpha)=0;
|
virtual void getPixel(int canvasId, int x, int y, unsigned char& red, unsigned char& green,unsigned char& blue, unsigned char& alpha)=0;
|
||||||
|
|||||||
@@ -233,6 +233,19 @@ struct CommonMultiBodyBase : public CommonExampleInterface
|
|||||||
|
|
||||||
virtual bool keyboardCallback(int key, int state)
|
virtual bool keyboardCallback(int key, int state)
|
||||||
{
|
{
|
||||||
|
if ((key==B3G_F3) && state && m_dynamicsWorld)
|
||||||
|
{
|
||||||
|
btDefaultSerializer* serializer = new btDefaultSerializer();
|
||||||
|
m_dynamicsWorld->serialize(serializer);
|
||||||
|
|
||||||
|
FILE* file = fopen("testFile.bullet","wb");
|
||||||
|
fwrite(serializer->getBufferPointer(),serializer->getCurrentBufferSize(),1, file);
|
||||||
|
fclose(file);
|
||||||
|
//b3Printf("btDefaultSerializer wrote testFile.bullet");
|
||||||
|
delete serializer;
|
||||||
|
return true;
|
||||||
|
|
||||||
|
}
|
||||||
return false;//don't handle this key
|
return false;//don't handle this key
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -259,6 +259,7 @@ SET(BulletExampleBrowser_SRCS
|
|||||||
../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp
|
../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp
|
||||||
../Importers/ImportMeshUtility/b3ImportMeshUtility.h
|
../Importers/ImportMeshUtility/b3ImportMeshUtility.h
|
||||||
../../Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp
|
../../Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp
|
||||||
|
../../Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp
|
||||||
../../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp
|
../../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp
|
||||||
../../Extras/Serialize/BulletFileLoader/bChunk.cpp
|
../../Extras/Serialize/BulletFileLoader/bChunk.cpp
|
||||||
../../Extras/Serialize/BulletFileLoader/bFile.cpp
|
../../Extras/Serialize/BulletFileLoader/bFile.cpp
|
||||||
|
|||||||
@@ -732,12 +732,11 @@ struct QuickCanvas : public Common2dCanvasInterface
|
|||||||
MyGraphWindow* m_gw[MAX_GRAPH_WINDOWS];
|
MyGraphWindow* m_gw[MAX_GRAPH_WINDOWS];
|
||||||
GraphingTexture* m_gt[MAX_GRAPH_WINDOWS];
|
GraphingTexture* m_gt[MAX_GRAPH_WINDOWS];
|
||||||
int m_curNumGraphWindows;
|
int m_curNumGraphWindows;
|
||||||
int m_curXpos;
|
|
||||||
|
|
||||||
QuickCanvas(GL3TexLoader* myTexLoader)
|
QuickCanvas(GL3TexLoader* myTexLoader)
|
||||||
:m_myTexLoader(myTexLoader),
|
:m_myTexLoader(myTexLoader),
|
||||||
m_curNumGraphWindows(0),
|
m_curNumGraphWindows(0)
|
||||||
m_curXpos(0)
|
|
||||||
{
|
{
|
||||||
for (int i=0;i<MAX_GRAPH_WINDOWS;i++)
|
for (int i=0;i<MAX_GRAPH_WINDOWS;i++)
|
||||||
{
|
{
|
||||||
@@ -746,7 +745,7 @@ struct QuickCanvas : public Common2dCanvasInterface
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
virtual ~QuickCanvas() {}
|
virtual ~QuickCanvas() {}
|
||||||
virtual int createCanvas(const char* canvasName, int width, int height)
|
virtual int createCanvas(const char* canvasName, int width, int height, int xPos, int yPos)
|
||||||
{
|
{
|
||||||
if (m_curNumGraphWindows<MAX_GRAPH_WINDOWS)
|
if (m_curNumGraphWindows<MAX_GRAPH_WINDOWS)
|
||||||
{
|
{
|
||||||
@@ -761,9 +760,8 @@ struct QuickCanvas : public Common2dCanvasInterface
|
|||||||
MyGraphInput input(gui2->getInternalData());
|
MyGraphInput input(gui2->getInternalData());
|
||||||
input.m_width=width;
|
input.m_width=width;
|
||||||
input.m_height=height;
|
input.m_height=height;
|
||||||
input.m_xPos = m_curXpos;//GUI will clamp it to the right//300;
|
input.m_xPos = xPos;
|
||||||
m_curXpos+=width+20;
|
input.m_yPos = yPos;
|
||||||
input.m_yPos = 10000;//GUI will clamp it to bottom
|
|
||||||
input.m_name=canvasName;
|
input.m_name=canvasName;
|
||||||
input.m_texName = canvasName;
|
input.m_texName = canvasName;
|
||||||
m_gt[slot] = new GraphingTexture;
|
m_gt[slot] = new GraphingTexture;
|
||||||
@@ -778,7 +776,6 @@ struct QuickCanvas : public Common2dCanvasInterface
|
|||||||
}
|
}
|
||||||
virtual void destroyCanvas(int canvasId)
|
virtual void destroyCanvas(int canvasId)
|
||||||
{
|
{
|
||||||
m_curXpos = 0;
|
|
||||||
btAssert(canvasId>=0);
|
btAssert(canvasId>=0);
|
||||||
delete m_gt[canvasId];
|
delete m_gt[canvasId];
|
||||||
m_gt[canvasId] = 0;
|
m_gt[canvasId] = 0;
|
||||||
@@ -1329,7 +1326,7 @@ void OpenGLExampleBrowser::update(float deltaTime)
|
|||||||
float camPos[3];
|
float camPos[3];
|
||||||
s_guiHelper->getRenderInterface()->getActiveCamera()->getCameraPosition(camPos);
|
s_guiHelper->getRenderInterface()->getActiveCamera()->getCameraPosition(camPos);
|
||||||
s_guiHelper->getRenderInterface()->getActiveCamera()->getCameraTargetPosition(camTarget);
|
s_guiHelper->getRenderInterface()->getActiveCamera()->getCameraTargetPosition(camTarget);
|
||||||
sprintf(msg,"camPos=%f,%f,%f, dist=%f, pitch=%f, yaw=%f,target=%f,%f,%f", camPos[0],camPos[1],camPos[2],camDist,pitch,yaw,camTarget[0],camTarget[1],camTarget[2]);
|
sprintf(msg,"camTargetPos=%2.2f,%2.2f,%2.2f, dist=%2.2f, pitch=%2.2f, yaw=%2.2f", camPos[0],camPos[1],camPos[2],camDist,pitch,yaw);
|
||||||
gui2->setStatusBarMessage(msg, true);
|
gui2->setStatusBarMessage(msg, true);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -440,7 +440,7 @@ void Win32Window::setWindowTitle(const char* titleChar)
|
|||||||
{
|
{
|
||||||
|
|
||||||
#ifdef _WIN64
|
#ifdef _WIN64
|
||||||
SetWindowText(m_data->m_hWnd, titleChar);
|
SetWindowTextA(m_data->m_hWnd, titleChar);
|
||||||
#else
|
#else
|
||||||
DWORD dwResult;
|
DWORD dwResult;
|
||||||
SendMessageTimeout(m_data->m_hWnd, WM_SETTEXT, 0,
|
SendMessageTimeout(m_data->m_hWnd, WM_SETTEXT, 0,
|
||||||
|
|||||||
@@ -142,7 +142,7 @@ void RaytracerPhysicsSetup::initPhysics()
|
|||||||
if (m_internalData->m_canvas)
|
if (m_internalData->m_canvas)
|
||||||
{
|
{
|
||||||
|
|
||||||
m_internalData->m_canvasIndex = m_internalData->m_canvas->createCanvas("raytracer",m_internalData->m_width,m_internalData->m_height);
|
m_internalData->m_canvasIndex = m_internalData->m_canvas->createCanvas("raytracer",m_internalData->m_width,m_internalData->m_height, 15,55);
|
||||||
for (int i=0;i<m_internalData->m_width;i++)
|
for (int i=0;i<m_internalData->m_width;i++)
|
||||||
{
|
{
|
||||||
for (int j=0;j<m_internalData->m_height;j++)
|
for (int j=0;j<m_internalData->m_height;j++)
|
||||||
|
|||||||
@@ -78,7 +78,7 @@ TimeSeriesCanvas::TimeSeriesCanvas(struct Common2dCanvasInterface* canvasInterfa
|
|||||||
|
|
||||||
if (canvasInterface)
|
if (canvasInterface)
|
||||||
{
|
{
|
||||||
m_internalData->m_canvasIndex = m_internalData->m_canvasInterface->createCanvas(windowTitle,m_internalData->m_width,m_internalData->m_height);
|
m_internalData->m_canvasIndex = m_internalData->m_canvasInterface->createCanvas(windowTitle,m_internalData->m_width,m_internalData->m_height,20,50);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -28,7 +28,7 @@ struct TestCanvasInterface2 : public Common2dCanvasInterface
|
|||||||
|
|
||||||
virtual ~TestCanvasInterface2()
|
virtual ~TestCanvasInterface2()
|
||||||
{}
|
{}
|
||||||
virtual int createCanvas(const char* canvasName, int width, int height)
|
virtual int createCanvas(const char* canvasName, int width, int height,int posX,int posY)
|
||||||
{
|
{
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -606,6 +606,19 @@ B3_SHARED_API int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle,
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API int b3JointControlSetMaximumVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double maximumVelocity)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||||
|
b3Assert(command);
|
||||||
|
if ((dofIndex>=0) && (dofIndex < MAX_DEGREE_OF_FREEDOM))
|
||||||
|
{
|
||||||
|
command->m_sendDesiredStateCommandArgument.m_rhsClamp[dofIndex] = maximumVelocity;
|
||||||
|
command->m_updateFlags |= SIM_DESIRED_STATE_HAS_RHS_CLAMP;
|
||||||
|
command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_RHS_CLAMP;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
B3_SHARED_API int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
|
B3_SHARED_API int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
|
||||||
{
|
{
|
||||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||||
|
|||||||
@@ -367,6 +367,8 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2(b3PhysicsC
|
|||||||
B3_SHARED_API int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value);
|
B3_SHARED_API int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value);
|
||||||
B3_SHARED_API int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value);
|
B3_SHARED_API int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value);
|
||||||
B3_SHARED_API int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value);
|
B3_SHARED_API int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value);
|
||||||
|
B3_SHARED_API int b3JointControlSetMaximumVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double maximumVelocity);
|
||||||
|
|
||||||
|
|
||||||
///Only use when controlMode is CONTROL_MODE_VELOCITY
|
///Only use when controlMode is CONTROL_MODE_VELOCITY
|
||||||
B3_SHARED_API int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); /* find a better name for dof/q/u indices, point to b3JointInfo */
|
B3_SHARED_API int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); /* find a better name for dof/q/u indices, point to b3JointInfo */
|
||||||
|
|||||||
@@ -22,8 +22,9 @@ struct MyMotorInfo2
|
|||||||
int m_qIndex;
|
int m_qIndex;
|
||||||
};
|
};
|
||||||
|
|
||||||
static int camVisualizerWidth = 320;//1024/3;
|
|
||||||
static int camVisualizerHeight = 240;//768/3;
|
static int camVisualizerWidth = 228;//1024/3;
|
||||||
|
static int camVisualizerHeight = 192;//768/3;
|
||||||
|
|
||||||
enum CustomCommands
|
enum CustomCommands
|
||||||
{
|
{
|
||||||
@@ -758,10 +759,10 @@ void PhysicsClientExample::initPhysics()
|
|||||||
m_canvas = m_guiHelper->get2dCanvasInterface();
|
m_canvas = m_guiHelper->get2dCanvasInterface();
|
||||||
if (m_canvas)
|
if (m_canvas)
|
||||||
{
|
{
|
||||||
|
m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data",camVisualizerWidth, camVisualizerHeight, 8,55);
|
||||||
|
m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data",camVisualizerWidth, camVisualizerHeight,8,75+camVisualizerHeight);
|
||||||
|
m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask",camVisualizerWidth, camVisualizerHeight,8,95+camVisualizerHeight*2);
|
||||||
|
|
||||||
m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data",camVisualizerWidth, camVisualizerHeight);
|
|
||||||
m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data",camVisualizerWidth, camVisualizerHeight);
|
|
||||||
m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask",camVisualizerWidth, camVisualizerHeight);
|
|
||||||
|
|
||||||
for (int i=0;i<camVisualizerWidth;i++)
|
for (int i=0;i<camVisualizerWidth;i++)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -29,6 +29,9 @@ struct PhysicsDirectInternalData
|
|||||||
btAlignedObjectArray<char> m_serverDNA;
|
btAlignedObjectArray<char> m_serverDNA;
|
||||||
SharedMemoryCommand m_command;
|
SharedMemoryCommand m_command;
|
||||||
SharedMemoryStatus m_serverStatus;
|
SharedMemoryStatus m_serverStatus;
|
||||||
|
|
||||||
|
SharedMemoryCommand m_tmpInfoRequestCommand;
|
||||||
|
SharedMemoryStatus m_tmpInfoStatus;
|
||||||
bool m_hasStatus;
|
bool m_hasStatus;
|
||||||
bool m_verboseOutput;
|
bool m_verboseOutput;
|
||||||
|
|
||||||
@@ -79,6 +82,9 @@ struct PhysicsDirectInternalData
|
|||||||
|
|
||||||
PhysicsDirect::PhysicsDirect(PhysicsCommandProcessorInterface* physSdk, bool passSdkOwnership)
|
PhysicsDirect::PhysicsDirect(PhysicsCommandProcessorInterface* physSdk, bool passSdkOwnership)
|
||||||
{
|
{
|
||||||
|
int sz = sizeof(SharedMemoryCommand);
|
||||||
|
int sz2 = sizeof(SharedMemoryStatus);
|
||||||
|
|
||||||
m_data = new PhysicsDirectInternalData;
|
m_data = new PhysicsDirectInternalData;
|
||||||
m_data->m_commandProcessor = physSdk;
|
m_data->m_commandProcessor = physSdk;
|
||||||
m_data->m_ownsCommandProcessor = passSdkOwnership;
|
m_data->m_ownsCommandProcessor = passSdkOwnership;
|
||||||
@@ -814,12 +820,12 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
|
|||||||
for (int i=0;i<numConstraints;i++)
|
for (int i=0;i<numConstraints;i++)
|
||||||
{
|
{
|
||||||
int constraintUid = serverCmd.m_sdfLoadedArgs.m_userConstraintUniqueIds[i];
|
int constraintUid = serverCmd.m_sdfLoadedArgs.m_userConstraintUniqueIds[i];
|
||||||
SharedMemoryCommand infoRequestCommand;
|
|
||||||
infoRequestCommand.m_type = CMD_USER_CONSTRAINT;
|
m_data->m_tmpInfoRequestCommand.m_type = CMD_USER_CONSTRAINT;
|
||||||
infoRequestCommand.m_updateFlags = USER_CONSTRAINT_REQUEST_INFO;
|
m_data->m_tmpInfoRequestCommand.m_updateFlags = USER_CONSTRAINT_REQUEST_INFO;
|
||||||
infoRequestCommand.m_userConstraintArguments.m_userConstraintUniqueId = constraintUid;
|
m_data->m_tmpInfoRequestCommand.m_userConstraintArguments.m_userConstraintUniqueId = constraintUid;
|
||||||
SharedMemoryStatus infoStatus;
|
|
||||||
bool hasStatus = m_data->m_commandProcessor->processCommand(infoRequestCommand, infoStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
|
bool hasStatus = m_data->m_commandProcessor->processCommand(m_data->m_tmpInfoRequestCommand, m_data->m_tmpInfoStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
|
||||||
|
|
||||||
|
|
||||||
b3Clock clock;
|
b3Clock clock;
|
||||||
@@ -828,13 +834,13 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
|
|||||||
|
|
||||||
while ((!hasStatus) && (clock.getTimeInSeconds()-startTime < timeOutInSeconds))
|
while ((!hasStatus) && (clock.getTimeInSeconds()-startTime < timeOutInSeconds))
|
||||||
{
|
{
|
||||||
hasStatus = m_data->m_commandProcessor->receiveStatus(infoStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
|
hasStatus = m_data->m_commandProcessor->receiveStatus(m_data->m_tmpInfoStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (hasStatus)
|
if (hasStatus)
|
||||||
{
|
{
|
||||||
int cid = infoStatus.m_userConstraintResultArgs.m_userConstraintUniqueId;
|
int cid = m_data->m_tmpInfoStatus.m_userConstraintResultArgs.m_userConstraintUniqueId;
|
||||||
m_data->m_userConstraintInfoMap.insert(cid,infoStatus.m_userConstraintResultArgs);
|
m_data->m_userConstraintInfoMap.insert(cid,m_data->m_tmpInfoStatus.m_userConstraintResultArgs);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -842,11 +848,11 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
|
|||||||
for (int i = 0; i<numBodies; i++)
|
for (int i = 0; i<numBodies; i++)
|
||||||
{
|
{
|
||||||
int bodyUniqueId = serverCmd.m_sdfLoadedArgs.m_bodyUniqueIds[i];
|
int bodyUniqueId = serverCmd.m_sdfLoadedArgs.m_bodyUniqueIds[i];
|
||||||
SharedMemoryCommand infoRequestCommand;
|
|
||||||
infoRequestCommand.m_type = CMD_REQUEST_BODY_INFO;
|
m_data->m_tmpInfoRequestCommand.m_type = CMD_REQUEST_BODY_INFO;
|
||||||
infoRequestCommand.m_sdfRequestInfoArgs.m_bodyUniqueId = bodyUniqueId;
|
m_data->m_tmpInfoRequestCommand.m_sdfRequestInfoArgs.m_bodyUniqueId = bodyUniqueId;
|
||||||
SharedMemoryStatus infoStatus;
|
|
||||||
bool hasStatus = m_data->m_commandProcessor->processCommand(infoRequestCommand, infoStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
|
bool hasStatus = m_data->m_commandProcessor->processCommand(m_data->m_tmpInfoRequestCommand, m_data->m_tmpInfoStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
|
||||||
|
|
||||||
|
|
||||||
b3Clock clock;
|
b3Clock clock;
|
||||||
@@ -855,12 +861,12 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
|
|||||||
|
|
||||||
while ((!hasStatus) && (clock.getTimeInSeconds()-startTime < timeOutInSeconds))
|
while ((!hasStatus) && (clock.getTimeInSeconds()-startTime < timeOutInSeconds))
|
||||||
{
|
{
|
||||||
hasStatus = m_data->m_commandProcessor->receiveStatus(infoStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
|
hasStatus = m_data->m_commandProcessor->receiveStatus(m_data->m_tmpInfoStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (hasStatus)
|
if (hasStatus)
|
||||||
{
|
{
|
||||||
processBodyJointInfo(bodyUniqueId, infoStatus);
|
processBodyJointInfo(bodyUniqueId, m_data->m_tmpInfoStatus);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|||||||
File diff suppressed because it is too large
Load Diff
@@ -25,6 +25,61 @@ class PhysicsServerCommandProcessor : public CommandProcessorInterface
|
|||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
|
||||||
|
bool processStateLoggingCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestCameraImageCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processSaveWorldCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processCreateCollisionShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processCreateVisualShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processCustomCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processUserDebugDrawCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processSetVRCameraStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestVREventsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestMouseEventsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestKeyboardEventsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestRaycastIntersectionsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestDebugLinesCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processSyncBodyInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processSendDesiredStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestActualStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestContactpointInformationCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestBodyInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processLoadSDFCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processCreateMultiBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processLoadURDFCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processLoadBunnyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processCreateSensorCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processProfileTimingCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestCollisionInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processForwardDynamicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestInternalDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processChangeDynamicsInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processSetAdditionalSearchPathCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processGetDynamicsInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestPhysicsSimulationParametersCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processSendPhysicsParametersCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processInitPoseCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processResetSimulationCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processCreateRigidBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processPickBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processMovePickedBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRemovePickingConstraintCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestAabbOverlapCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestOpenGLVisualizeCameraCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processConfigureOpenGLVisualizerCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processInverseDynamicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processCalculateJacobianCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processCalculateMassMatrixCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processApplyExternalForceCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRemoveBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processCreateUserConstraintCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processCalculateInverseKinematicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processRequestVisualShapeInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processUpdateVisualShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processChangeTextureCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processLoadTextureCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processLoadBulletCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processSaveBulletCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
bool processLoadMJCFCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
|
||||||
|
|
||||||
bool loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody, int flags, btScalar globalScaling);
|
bool loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody, int flags, btScalar globalScaling);
|
||||||
|
|||||||
@@ -30,8 +30,8 @@ bool gActivedVRRealTimeSimulation = false;
|
|||||||
|
|
||||||
bool gEnableSyncPhysicsRendering= true;
|
bool gEnableSyncPhysicsRendering= true;
|
||||||
bool gEnableUpdateDebugDrawLines = true;
|
bool gEnableUpdateDebugDrawLines = true;
|
||||||
static int gCamVisualizerWidth = 320;
|
static int gCamVisualizerWidth = 228;
|
||||||
static int gCamVisualizerHeight = 240;
|
static int gCamVisualizerHeight = 192;
|
||||||
|
|
||||||
static bool gEnableDefaultKeyboardShortcuts = true;
|
static bool gEnableDefaultKeyboardShortcuts = true;
|
||||||
static bool gEnableDefaultMousePicking = true;
|
static bool gEnableDefaultMousePicking = true;
|
||||||
@@ -1751,9 +1751,9 @@ void PhysicsServerExample::initPhysics()
|
|||||||
{
|
{
|
||||||
|
|
||||||
|
|
||||||
m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data",gCamVisualizerWidth, gCamVisualizerHeight);
|
m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data",gCamVisualizerWidth, gCamVisualizerHeight, 8,55);
|
||||||
//m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data",gCamVisualizerWidth, gCamVisualizerHeight);
|
m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data",gCamVisualizerWidth, gCamVisualizerHeight,8,75+gCamVisualizerHeight);
|
||||||
//m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask",gCamVisualizerWidth, gCamVisualizerHeight);
|
m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask",gCamVisualizerWidth, gCamVisualizerHeight,8,95+gCamVisualizerHeight*2);
|
||||||
|
|
||||||
for (int i=0;i<gCamVisualizerWidth;i++)
|
for (int i=0;i<gCamVisualizerWidth;i++)
|
||||||
{
|
{
|
||||||
@@ -1898,6 +1898,60 @@ void PhysicsServerExample::updateGraphics()
|
|||||||
int flag = m_multiThreadedHelper->m_visualizerFlag;
|
int flag = m_multiThreadedHelper->m_visualizerFlag;
|
||||||
int enable = m_multiThreadedHelper->m_visualizerEnable;
|
int enable = m_multiThreadedHelper->m_visualizerEnable;
|
||||||
|
|
||||||
|
if (flag == COV_ENABLE_RGB_BUFFER_PREVIEW)
|
||||||
|
{
|
||||||
|
if (enable)
|
||||||
|
{
|
||||||
|
if (m_canvasRGBIndex<0)
|
||||||
|
{
|
||||||
|
m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data",gCamVisualizerWidth, gCamVisualizerHeight, 8,55);
|
||||||
|
}
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
if (m_canvasRGBIndex>=0)
|
||||||
|
{
|
||||||
|
m_canvas->destroyCanvas(m_canvasRGBIndex);
|
||||||
|
m_canvasRGBIndex = -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (flag == COV_ENABLE_DEPTH_BUFFER_PREVIEW)
|
||||||
|
{
|
||||||
|
if (enable)
|
||||||
|
{
|
||||||
|
if (m_canvasDepthIndex<0)
|
||||||
|
{
|
||||||
|
m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data",gCamVisualizerWidth, gCamVisualizerHeight,8,75+gCamVisualizerHeight);
|
||||||
|
}
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
if (m_canvasDepthIndex>=0)
|
||||||
|
{
|
||||||
|
m_canvas->destroyCanvas(m_canvasDepthIndex);
|
||||||
|
m_canvasDepthIndex = -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (flag == COV_ENABLE_SEGMENTATION_MARK_PREVIEW)
|
||||||
|
{
|
||||||
|
if (enable)
|
||||||
|
{
|
||||||
|
if (m_canvasSegMaskIndex<0)
|
||||||
|
{
|
||||||
|
m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask",gCamVisualizerWidth, gCamVisualizerHeight,8,95+gCamVisualizerHeight*2);
|
||||||
|
}
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
if (m_canvasSegMaskIndex>=0)
|
||||||
|
{
|
||||||
|
m_canvas->destroyCanvas(m_canvasSegMaskIndex);
|
||||||
|
m_canvasSegMaskIndex = -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (flag==COV_ENABLE_VR_TELEPORTING)
|
if (flag==COV_ENABLE_VR_TELEPORTING)
|
||||||
{
|
{
|
||||||
gEnableTeleporting = (enable!=0);
|
gEnableTeleporting = (enable!=0);
|
||||||
@@ -2042,8 +2096,9 @@ void PhysicsServerExample::updateGraphics()
|
|||||||
int startSegIndex = m_multiThreadedHelper->m_startPixelIndex;
|
int startSegIndex = m_multiThreadedHelper->m_startPixelIndex;
|
||||||
int endSegIndex = startSegIndex + (*m_multiThreadedHelper->m_numPixelsCopied);
|
int endSegIndex = startSegIndex + (*m_multiThreadedHelper->m_numPixelsCopied);
|
||||||
|
|
||||||
btScalar frustumZNear = m_multiThreadedHelper->m_projectionMatrix[14]/(m_multiThreadedHelper->m_projectionMatrix[10]-1);
|
//btScalar frustumZNear = m_multiThreadedHelper->m_projectionMatrix[14]/(m_multiThreadedHelper->m_projectionMatrix[10]-1);
|
||||||
btScalar frustumZFar = 20;//m_multiThreadedHelper->m_projectionMatrix[14]/(m_multiThreadedHelper->m_projectionMatrix[10]+1);
|
//btScalar frustumZFar = m_multiThreadedHelper->m_projectionMatrix[14]/(m_multiThreadedHelper->m_projectionMatrix[10]+1);
|
||||||
|
|
||||||
|
|
||||||
for (int i=0;i<gCamVisualizerWidth;i++)
|
for (int i=0;i<gCamVisualizerWidth;i++)
|
||||||
{
|
{
|
||||||
@@ -2077,17 +2132,16 @@ void PhysicsServerExample::updateGraphics()
|
|||||||
if (depthValue>-1e20)
|
if (depthValue>-1e20)
|
||||||
{
|
{
|
||||||
int rgb = 0;
|
int rgb = 0;
|
||||||
btScalar minDepthValue = 0.98;//todo: compute more reasonably min/max depth range
|
btScalar frustumZNear = 0.1;
|
||||||
btScalar maxDepthValue = 1;
|
btScalar frustumZFar = 30;
|
||||||
|
btScalar minDepthValue = frustumZNear;//todo: compute more reasonably min/max depth range
|
||||||
|
btScalar maxDepthValue = frustumZFar;
|
||||||
|
|
||||||
|
float depth = depthValue;
|
||||||
|
btScalar linearDepth = 255.*(2.0 * frustumZNear) / (frustumZFar + frustumZNear - depth * (frustumZFar - frustumZNear));
|
||||||
|
btClamp(linearDepth, btScalar(0),btScalar(255));
|
||||||
|
rgb = linearDepth;
|
||||||
|
|
||||||
if (maxDepthValue!=minDepthValue)
|
|
||||||
{
|
|
||||||
rgb = (depthValue-minDepthValue)*(255. / (btFabs(maxDepthValue-minDepthValue)));
|
|
||||||
if (rgb<0 || rgb>255)
|
|
||||||
{
|
|
||||||
//printf("rgb=%d\n",rgb);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
m_canvas->setPixel(m_canvasDepthIndex,i,j,
|
m_canvas->setPixel(m_canvasDepthIndex,i,j,
|
||||||
rgb,
|
rgb,
|
||||||
rgb,
|
rgb,
|
||||||
|
|||||||
@@ -362,6 +362,7 @@ struct SendDesiredStateArgs
|
|||||||
//PD parameters in case m_controlMode == CONTROL_MODE_POSITION_VELOCITY_PD
|
//PD parameters in case m_controlMode == CONTROL_MODE_POSITION_VELOCITY_PD
|
||||||
double m_Kp[MAX_DEGREE_OF_FREEDOM];//indexed by degree of freedom, 6 for base, and then the dofs for each link
|
double m_Kp[MAX_DEGREE_OF_FREEDOM];//indexed by degree of freedom, 6 for base, and then the dofs for each link
|
||||||
double m_Kd[MAX_DEGREE_OF_FREEDOM];//indexed by degree of freedom, 6 for base, and then the dofs for each link
|
double m_Kd[MAX_DEGREE_OF_FREEDOM];//indexed by degree of freedom, 6 for base, and then the dofs for each link
|
||||||
|
double m_rhsClamp[MAX_DEGREE_OF_FREEDOM];
|
||||||
|
|
||||||
int m_hasDesiredStateFlags[MAX_DEGREE_OF_FREEDOM];
|
int m_hasDesiredStateFlags[MAX_DEGREE_OF_FREEDOM];
|
||||||
|
|
||||||
@@ -389,6 +390,7 @@ enum EnumSimDesiredStateUpdateFlags
|
|||||||
SIM_DESIRED_STATE_HAS_KD=4,
|
SIM_DESIRED_STATE_HAS_KD=4,
|
||||||
SIM_DESIRED_STATE_HAS_KP=8,
|
SIM_DESIRED_STATE_HAS_KP=8,
|
||||||
SIM_DESIRED_STATE_HAS_MAX_FORCE=16,
|
SIM_DESIRED_STATE_HAS_MAX_FORCE=16,
|
||||||
|
SIM_DESIRED_STATE_HAS_RHS_CLAMP=32
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -355,7 +355,7 @@ enum b3VREventType
|
|||||||
#define MAX_KEYBOARD_EVENTS 256
|
#define MAX_KEYBOARD_EVENTS 256
|
||||||
#define MAX_MOUSE_EVENTS 256
|
#define MAX_MOUSE_EVENTS 256
|
||||||
|
|
||||||
#define MAX_SDF_BODIES 1024
|
#define MAX_SDF_BODIES 512
|
||||||
|
|
||||||
|
|
||||||
enum b3VRButtonInfo
|
enum b3VRButtonInfo
|
||||||
@@ -600,6 +600,10 @@ enum b3ConfigureDebugVisualizerEnum
|
|||||||
COV_ENABLE_MOUSE_PICKING,
|
COV_ENABLE_MOUSE_PICKING,
|
||||||
COV_ENABLE_Y_AXIS_UP,
|
COV_ENABLE_Y_AXIS_UP,
|
||||||
COV_ENABLE_TINY_RENDERER,
|
COV_ENABLE_TINY_RENDERER,
|
||||||
|
COV_ENABLE_RGB_BUFFER_PREVIEW,
|
||||||
|
COV_ENABLE_DEPTH_BUFFER_PREVIEW,
|
||||||
|
COV_ENABLE_SEGMENTATION_MARK_PREVIEW,
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
enum b3AddUserDebugItemEnum
|
enum b3AddUserDebugItemEnum
|
||||||
|
|||||||
@@ -772,12 +772,13 @@ void TinyRendererVisualShapeConverter::resetCamera(float camDist, float yaw, flo
|
|||||||
|
|
||||||
void TinyRendererVisualShapeConverter::clearBuffers(TGAColor& clearColor)
|
void TinyRendererVisualShapeConverter::clearBuffers(TGAColor& clearColor)
|
||||||
{
|
{
|
||||||
|
float farPlane = m_data->m_camera.getCameraFrustumFar();
|
||||||
for(int y=0;y<m_data->m_swHeight;++y)
|
for(int y=0;y<m_data->m_swHeight;++y)
|
||||||
{
|
{
|
||||||
for(int x=0;x<m_data->m_swWidth;++x)
|
for(int x=0;x<m_data->m_swWidth;++x)
|
||||||
{
|
{
|
||||||
m_data->m_rgbColorBuffer.set(x,y,clearColor);
|
m_data->m_rgbColorBuffer.set(x,y,clearColor);
|
||||||
m_data->m_depthBuffer[x+y*m_data->m_swWidth] = -1e30f;
|
m_data->m_depthBuffer[x+y*m_data->m_swWidth] = -farPlane;
|
||||||
m_data->m_shadowBuffer[x+y*m_data->m_swWidth] = -1e30f;
|
m_data->m_shadowBuffer[x+y*m_data->m_swWidth] = -1e30f;
|
||||||
m_data->m_segmentationMaskBuffer[x+y*m_data->m_swWidth] = -1;
|
m_data->m_segmentationMaskBuffer[x+y*m_data->m_swWidth] = -1;
|
||||||
}
|
}
|
||||||
@@ -806,13 +807,13 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
|
|||||||
clearColor.bgra[2] = 255;
|
clearColor.bgra[2] = 255;
|
||||||
clearColor.bgra[3] = 255;
|
clearColor.bgra[3] = 255;
|
||||||
|
|
||||||
clearBuffers(clearColor);
|
|
||||||
float near = projMat[14]/(projMat[10]-1);
|
float near = projMat[14]/(projMat[10]-1);
|
||||||
float far = projMat[14]/(projMat[10]+1);
|
float far = projMat[14]/(projMat[10]+1);
|
||||||
|
|
||||||
m_data->m_camera.setCameraFrustumNear( near);
|
m_data->m_camera.setCameraFrustumNear( near);
|
||||||
m_data->m_camera.setCameraFrustumFar(far);
|
m_data->m_camera.setCameraFrustumFar(far);
|
||||||
|
|
||||||
|
clearBuffers(clearColor);
|
||||||
|
|
||||||
ATTRIBUTE_ALIGNED16(btScalar modelMat[16]);
|
ATTRIBUTE_ALIGNED16(btScalar modelMat[16]);
|
||||||
|
|
||||||
@@ -1025,16 +1026,20 @@ void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixels
|
|||||||
{
|
{
|
||||||
if (depthBuffer)
|
if (depthBuffer)
|
||||||
{
|
{
|
||||||
float distance = -m_data->m_depthBuffer[i+startPixelIndex];
|
|
||||||
float farPlane = m_data->m_camera.getCameraFrustumFar();
|
float farPlane = m_data->m_camera.getCameraFrustumFar();
|
||||||
float nearPlane = m_data->m_camera.getCameraFrustumNear();
|
float nearPlane = m_data->m_camera.getCameraFrustumNear();
|
||||||
|
|
||||||
btClamp(distance,nearPlane,farPlane);
|
// TinyRenderer returns clip coordinates, transform to eye coordinates first
|
||||||
|
float z_c = -m_data->m_depthBuffer[i+startPixelIndex];
|
||||||
|
// float distance = (farPlane - nearPlane) / (farPlane + nearPlane) * (z_c + 2. * farPlane * nearPlane / (farPlane - nearPlane));
|
||||||
|
|
||||||
// the depth buffer value is between 0 and 1
|
// The depth buffer value is between 0 and 1
|
||||||
float a = farPlane / (farPlane - nearPlane);
|
// float a = farPlane / (farPlane - nearPlane);
|
||||||
float b = farPlane * nearPlane / (nearPlane - farPlane);
|
// float b = farPlane * nearPlane / (nearPlane - farPlane);
|
||||||
depthBuffer[i] = a + b / distance;
|
// depthBuffer[i] = a + b / distance;
|
||||||
|
|
||||||
|
// Simply the above expressions
|
||||||
|
depthBuffer[i] = farPlane * (nearPlane + z_c) / (2. * farPlane * nearPlane + farPlane * z_c - nearPlane * z_c);
|
||||||
}
|
}
|
||||||
if (segmentationMaskBuffer)
|
if (segmentationMaskBuffer)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -13,7 +13,7 @@
|
|||||||
|
|
||||||
typedef HMODULE B3_DYNLIB_HANDLE;
|
typedef HMODULE B3_DYNLIB_HANDLE;
|
||||||
|
|
||||||
#define B3_DYNLIB_OPEN LoadLibrary
|
#define B3_DYNLIB_OPEN LoadLibraryA
|
||||||
#define B3_DYNLIB_CLOSE FreeLibrary
|
#define B3_DYNLIB_CLOSE FreeLibrary
|
||||||
#define B3_DYNLIB_IMPORT GetProcAddress
|
#define B3_DYNLIB_IMPORT GetProcAddress
|
||||||
#else
|
#else
|
||||||
|
|||||||
@@ -111,6 +111,7 @@ files {
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (_OPTIONS["enable_static_vr_plugin"]) then
|
if (_OPTIONS["enable_static_vr_plugin"]) then
|
||||||
|
defines("STATIC_LINK_VR_PLUGIN")
|
||||||
files {"plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
|
files {"plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
|
||||||
end
|
end
|
||||||
|
|
||||||
@@ -208,6 +209,7 @@ files {
|
|||||||
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
|
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
|
||||||
}
|
}
|
||||||
if (_OPTIONS["enable_static_vr_plugin"]) then
|
if (_OPTIONS["enable_static_vr_plugin"]) then
|
||||||
|
defines("STATIC_LINK_VR_PLUGIN")
|
||||||
files {"plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
|
files {"plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
|
||||||
end
|
end
|
||||||
|
|
||||||
@@ -363,6 +365,7 @@ if os.is("Windows") then
|
|||||||
"../ThirdPartyLibs/openvr/samples/shared/Vectors.h",
|
"../ThirdPartyLibs/openvr/samples/shared/Vectors.h",
|
||||||
}
|
}
|
||||||
if (_OPTIONS["enable_static_vr_plugin"]) then
|
if (_OPTIONS["enable_static_vr_plugin"]) then
|
||||||
|
defines("STATIC_LINK_VR_PLUGIN")
|
||||||
files {"plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
|
files {"plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
|
||||||
end
|
end
|
||||||
|
|
||||||
|
|||||||
@@ -51,14 +51,14 @@ LinearMapR2 LinearMapR2::Inverse() const // Returns inverse
|
|||||||
{
|
{
|
||||||
|
|
||||||
|
|
||||||
register double detInv = 1.0/(m11*m22 - m12*m21) ;
|
double detInv = 1.0/(m11*m22 - m12*m21) ;
|
||||||
|
|
||||||
return( LinearMapR2( m22*detInv, -m21*detInv, -m12*detInv, m11*detInv ) );
|
return( LinearMapR2( m22*detInv, -m21*detInv, -m12*detInv, m11*detInv ) );
|
||||||
}
|
}
|
||||||
|
|
||||||
LinearMapR2& LinearMapR2::Invert() // Converts into inverse.
|
LinearMapR2& LinearMapR2::Invert() // Converts into inverse.
|
||||||
{
|
{
|
||||||
register double detInv = 1.0/(m11*m22 - m12*m21) ;
|
double detInv = 1.0/(m11*m22 - m12*m21) ;
|
||||||
|
|
||||||
double temp;
|
double temp;
|
||||||
temp = m11*detInv;
|
temp = m11*detInv;
|
||||||
|
|||||||
@@ -90,7 +90,7 @@ public:
|
|||||||
VectorR2& operator*= ( double m )
|
VectorR2& operator*= ( double m )
|
||||||
{ x*=m; y*=m; return(*this); }
|
{ x*=m; y*=m; return(*this); }
|
||||||
VectorR2& operator/= ( double m )
|
VectorR2& operator/= ( double m )
|
||||||
{ register double mInv = 1.0/m;
|
{ double mInv = 1.0/m;
|
||||||
x*=mInv; y*=mInv;
|
x*=mInv; y*=mInv;
|
||||||
return(*this); }
|
return(*this); }
|
||||||
VectorR2 operator- () const { return ( VectorR2(-x, -y) ); }
|
VectorR2 operator- () const { return ( VectorR2(-x, -y) ); }
|
||||||
@@ -108,7 +108,7 @@ public:
|
|||||||
VectorR2& MakeUnit(); // Normalize() with error checking
|
VectorR2& MakeUnit(); // Normalize() with error checking
|
||||||
VectorR2& ReNormalize();
|
VectorR2& ReNormalize();
|
||||||
bool IsUnit( double tolerance = 1.0e-15 ) const
|
bool IsUnit( double tolerance = 1.0e-15 ) const
|
||||||
{ register double norm = Norm();
|
{ double norm = Norm();
|
||||||
return ( 1.0+tolerance>=norm && norm>=1.0-tolerance ); }
|
return ( 1.0+tolerance>=norm && norm>=1.0-tolerance ); }
|
||||||
bool IsZero() const { return ( x==0.0 && y==0.0 ); }
|
bool IsZero() const { return ( x==0.0 && y==0.0 ); }
|
||||||
bool NearZero(double tolerance) const { return( MaxAbs()<=tolerance );}
|
bool NearZero(double tolerance) const { return( MaxAbs()<=tolerance );}
|
||||||
@@ -369,7 +369,7 @@ inline VectorR2& VectorR2::MakeUnit () // Convert to unit vector (or leave zero
|
|||||||
inline VectorR2& VectorR2::ReNormalize() // Convert near unit back to unit
|
inline VectorR2& VectorR2::ReNormalize() // Convert near unit back to unit
|
||||||
{
|
{
|
||||||
double nSq = NormSq();
|
double nSq = NormSq();
|
||||||
register double mFact = 1.0-0.5*(nSq-1.0); // Multiplicative factor
|
double mFact = 1.0-0.5*(nSq-1.0); // Multiplicative factor
|
||||||
*this *= mFact;
|
*this *= mFact;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
@@ -395,7 +395,7 @@ inline VectorR2& VectorR2::Rotate( double costheta, double sintheta )
|
|||||||
|
|
||||||
inline double VectorR2::MaxAbs() const
|
inline double VectorR2::MaxAbs() const
|
||||||
{
|
{
|
||||||
register double m;
|
double m;
|
||||||
m = (x>=0.0) ? x : -x;
|
m = (x>=0.0) ? x : -x;
|
||||||
if ( y>m ) m=y;
|
if ( y>m ) m=y;
|
||||||
else if ( -y >m ) m = -y;
|
else if ( -y >m ) m = -y;
|
||||||
@@ -410,17 +410,17 @@ inline VectorR2 operator-( const VectorR2& u, const VectorR2& v )
|
|||||||
{
|
{
|
||||||
return VectorR2(u.x-v.x, u.y-v.y );
|
return VectorR2(u.x-v.x, u.y-v.y );
|
||||||
}
|
}
|
||||||
inline VectorR2 operator*( const VectorR2& u, register double m)
|
inline VectorR2 operator*( const VectorR2& u, double m)
|
||||||
{
|
{
|
||||||
return VectorR2( u.x*m, u.y*m );
|
return VectorR2( u.x*m, u.y*m );
|
||||||
}
|
}
|
||||||
inline VectorR2 operator*( register double m, const VectorR2& u)
|
inline VectorR2 operator*( double m, const VectorR2& u)
|
||||||
{
|
{
|
||||||
return VectorR2( u.x*m, u.y*m );
|
return VectorR2( u.x*m, u.y*m );
|
||||||
}
|
}
|
||||||
inline VectorR2 operator/( const VectorR2& u, double m)
|
inline VectorR2 operator/( const VectorR2& u, double m)
|
||||||
{
|
{
|
||||||
register double mInv = 1.0/m;
|
double mInv = 1.0/m;
|
||||||
return VectorR2( u.x*mInv, u.y*mInv );
|
return VectorR2( u.x*mInv, u.y*mInv );
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -454,7 +454,7 @@ inline VectorR2::VectorR2( const VectorHgR2& uH )
|
|||||||
|
|
||||||
inline double NormalizeError (const VectorR2& u)
|
inline double NormalizeError (const VectorR2& u)
|
||||||
{
|
{
|
||||||
register double discrepancy;
|
double discrepancy;
|
||||||
discrepancy = u.x*u.x + u.y*u.y - 1.0;
|
discrepancy = u.x*u.x + u.y*u.y - 1.0;
|
||||||
if ( discrepancy < 0.0 ) {
|
if ( discrepancy < 0.0 ) {
|
||||||
discrepancy = -discrepancy;
|
discrepancy = -discrepancy;
|
||||||
@@ -626,7 +626,7 @@ inline double Matrix2x2::Diagonal( int i )
|
|||||||
}
|
}
|
||||||
inline void Matrix2x2::MakeTranspose() // Transposes it.
|
inline void Matrix2x2::MakeTranspose() // Transposes it.
|
||||||
{
|
{
|
||||||
register double temp;
|
double temp;
|
||||||
temp = m12;
|
temp = m12;
|
||||||
m12 = m21;
|
m12 = m21;
|
||||||
m21=temp;
|
m21=temp;
|
||||||
@@ -647,8 +647,8 @@ inline void Matrix2x2::operator*= (const Matrix2x2& B) // Matrix product
|
|||||||
|
|
||||||
inline Matrix2x2& Matrix2x2::ReNormalize() // Re-normalizes nearly orthonormal matrix
|
inline Matrix2x2& Matrix2x2::ReNormalize() // Re-normalizes nearly orthonormal matrix
|
||||||
{
|
{
|
||||||
register double alpha = m11*m11+m21*m21; // First column's norm squared
|
double alpha = m11*m11+m21*m21; // First column's norm squared
|
||||||
register double beta = m12*m12+m22*m22; // Second column's norm squared
|
double beta = m12*m12+m22*m22; // Second column's norm squared
|
||||||
alpha = 1.0 - 0.5*(alpha-1.0); // Get mult. factor
|
alpha = 1.0 - 0.5*(alpha-1.0); // Get mult. factor
|
||||||
beta = 1.0 - 0.5*(beta-1.0);
|
beta = 1.0 - 0.5*(beta-1.0);
|
||||||
m11 *= alpha; // Renormalize first column
|
m11 *= alpha; // Renormalize first column
|
||||||
@@ -657,7 +657,7 @@ inline Matrix2x2& Matrix2x2::ReNormalize() // Re-normalizes nearly orthonormal m
|
|||||||
m22 *= beta;
|
m22 *= beta;
|
||||||
alpha = m11*m12+m21*m22; // Columns' inner product
|
alpha = m11*m12+m21*m22; // Columns' inner product
|
||||||
alpha *= 0.5; // times 1/2
|
alpha *= 0.5; // times 1/2
|
||||||
register double temp;
|
double temp;
|
||||||
temp = m11-alpha*m12; // Subtract alpha times other column
|
temp = m11-alpha*m12; // Subtract alpha times other column
|
||||||
m12 -= alpha*m11;
|
m12 -= alpha*m11;
|
||||||
m11 = temp;
|
m11 = temp;
|
||||||
@@ -671,8 +671,8 @@ inline Matrix2x2& Matrix2x2::ReNormalize() // Re-normalizes nearly orthonormal m
|
|||||||
// Mostly intended for diagnostic purposes.
|
// Mostly intended for diagnostic purposes.
|
||||||
inline double NormalizeError( const Matrix2x2& A)
|
inline double NormalizeError( const Matrix2x2& A)
|
||||||
{
|
{
|
||||||
register double discrepancy;
|
double discrepancy;
|
||||||
register double newdisc;
|
double newdisc;
|
||||||
discrepancy = A.m11*A.m11 + A.m21*A.m21 -1.0; // First column - inner product - 1
|
discrepancy = A.m11*A.m11 + A.m21*A.m21 -1.0; // First column - inner product - 1
|
||||||
if (discrepancy<0.0) {
|
if (discrepancy<0.0) {
|
||||||
discrepancy = -discrepancy;
|
discrepancy = -discrepancy;
|
||||||
@@ -780,7 +780,7 @@ inline LinearMapR2 operator- (const LinearMapR2& A, const LinearMapR2& B)
|
|||||||
A.m12-B.m12, A.m22-B.m22 ) );
|
A.m12-B.m12, A.m22-B.m22 ) );
|
||||||
}
|
}
|
||||||
|
|
||||||
inline LinearMapR2& LinearMapR2::operator*= (register double b)
|
inline LinearMapR2& LinearMapR2::operator*= ( double b)
|
||||||
{
|
{
|
||||||
m11 *= b;
|
m11 *= b;
|
||||||
m12 *= b;
|
m12 *= b;
|
||||||
@@ -789,13 +789,13 @@ inline LinearMapR2& LinearMapR2::operator*= (register double b)
|
|||||||
return ( *this);
|
return ( *this);
|
||||||
}
|
}
|
||||||
|
|
||||||
inline LinearMapR2 operator* ( const LinearMapR2& A, register double b)
|
inline LinearMapR2 operator* ( const LinearMapR2& A, double b)
|
||||||
{
|
{
|
||||||
return( LinearMapR2( A.m11*b, A.m21*b,
|
return( LinearMapR2( A.m11*b, A.m21*b,
|
||||||
A.m12*b, A.m22*b ) );
|
A.m12*b, A.m22*b ) );
|
||||||
}
|
}
|
||||||
|
|
||||||
inline LinearMapR2 operator* ( register double b, const LinearMapR2& A)
|
inline LinearMapR2 operator* ( double b, const LinearMapR2& A)
|
||||||
{
|
{
|
||||||
return( LinearMapR2( A.m11*b, A.m21*b,
|
return( LinearMapR2( A.m11*b, A.m21*b,
|
||||||
A.m12*b, A.m22*b ) );
|
A.m12*b, A.m22*b ) );
|
||||||
@@ -803,13 +803,13 @@ inline LinearMapR2 operator* ( register double b, const LinearMapR2& A)
|
|||||||
|
|
||||||
inline LinearMapR2 operator/ ( const LinearMapR2& A, double b)
|
inline LinearMapR2 operator/ ( const LinearMapR2& A, double b)
|
||||||
{
|
{
|
||||||
register double bInv = 1.0/b;
|
double bInv = 1.0/b;
|
||||||
return ( A*bInv );
|
return ( A*bInv );
|
||||||
}
|
}
|
||||||
|
|
||||||
inline LinearMapR2& LinearMapR2::operator/= (register double b)
|
inline LinearMapR2& LinearMapR2::operator/= ( double b)
|
||||||
{
|
{
|
||||||
register double bInv = 1.0/b;
|
double bInv = 1.0/b;
|
||||||
return ( *this *= bInv );
|
return ( *this *= bInv );
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -47,7 +47,7 @@ const Matrix3x4 Matrix3x4::Identity(1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0,
|
|||||||
|
|
||||||
double VectorR3::MaxAbs() const
|
double VectorR3::MaxAbs() const
|
||||||
{
|
{
|
||||||
register double m;
|
double m;
|
||||||
m = (x>0.0) ? x : -x;
|
m = (x>0.0) ? x : -x;
|
||||||
if ( y>m ) m=y;
|
if ( y>m ) m=y;
|
||||||
else if ( -y >m ) m = -y;
|
else if ( -y >m ) m = -y;
|
||||||
@@ -124,9 +124,9 @@ VectorR3& VectorR3::RotateUnitInDirection ( const VectorR3& dir)
|
|||||||
|
|
||||||
Matrix3x3& Matrix3x3::ReNormalize() // Re-normalizes nearly orthonormal matrix
|
Matrix3x3& Matrix3x3::ReNormalize() // Re-normalizes nearly orthonormal matrix
|
||||||
{
|
{
|
||||||
register double alpha = m11*m11+m21*m21+m31*m31; // First column's norm squared
|
double alpha = m11*m11+m21*m21+m31*m31; // First column's norm squared
|
||||||
register double beta = m12*m12+m22*m22+m32*m32; // Second column's norm squared
|
double beta = m12*m12+m22*m22+m32*m32; // Second column's norm squared
|
||||||
register double gamma = m13*m13+m23*m23+m33*m33; // Third column's norm squared
|
double gamma = m13*m13+m23*m23+m33*m33; // Third column's norm squared
|
||||||
alpha = 1.0 - 0.5*(alpha-1.0); // Get mult. factor
|
alpha = 1.0 - 0.5*(alpha-1.0); // Get mult. factor
|
||||||
beta = 1.0 - 0.5*(beta-1.0);
|
beta = 1.0 - 0.5*(beta-1.0);
|
||||||
gamma = 1.0 - 0.5*(gamma-1.0);
|
gamma = 1.0 - 0.5*(gamma-1.0);
|
||||||
@@ -145,7 +145,7 @@ Matrix3x3& Matrix3x3::ReNormalize() // Re-normalizes nearly orthonormal matrix
|
|||||||
alpha *= 0.5;
|
alpha *= 0.5;
|
||||||
beta *= 0.5;
|
beta *= 0.5;
|
||||||
gamma *= 0.5;
|
gamma *= 0.5;
|
||||||
register double temp1, temp2;
|
double temp1, temp2;
|
||||||
temp1 = m11-alpha*m12-beta*m13; // Update row1
|
temp1 = m11-alpha*m12-beta*m13; // Update row1
|
||||||
temp2 = m12-alpha*m11-gamma*m13;
|
temp2 = m12-alpha*m11-gamma*m13;
|
||||||
m13 -= beta*m11+gamma*m12;
|
m13 -= beta*m11+gamma*m12;
|
||||||
@@ -199,7 +199,7 @@ VectorR3 Matrix3x3::Solve(const VectorR3& u) const // Returns solution
|
|||||||
double sd23 = m31*m12-m11*m32;
|
double sd23 = m31*m12-m11*m32;
|
||||||
double sd33 = m11*m22-m21*m12;
|
double sd33 = m11*m22-m21*m12;
|
||||||
|
|
||||||
register double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13);
|
double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13);
|
||||||
|
|
||||||
double rx = (u.x*sd11 + u.y*sd21 + u.z*sd31)*detInv;
|
double rx = (u.x*sd11 + u.y*sd21 + u.z*sd31)*detInv;
|
||||||
double ry = (u.x*sd12 + u.y*sd22 + u.z*sd32)*detInv;
|
double ry = (u.x*sd12 + u.y*sd22 + u.z*sd32)*detInv;
|
||||||
@@ -215,9 +215,9 @@ VectorR3 Matrix3x3::Solve(const VectorR3& u) const // Returns solution
|
|||||||
|
|
||||||
Matrix3x4& Matrix3x4::ReNormalize() // Re-normalizes nearly orthonormal matrix
|
Matrix3x4& Matrix3x4::ReNormalize() // Re-normalizes nearly orthonormal matrix
|
||||||
{
|
{
|
||||||
register double alpha = m11*m11+m21*m21+m31*m31; // First column's norm squared
|
double alpha = m11*m11+m21*m21+m31*m31; // First column's norm squared
|
||||||
register double beta = m12*m12+m22*m22+m32*m32; // Second column's norm squared
|
double beta = m12*m12+m22*m22+m32*m32; // Second column's norm squared
|
||||||
register double gamma = m13*m13+m23*m23+m33*m33; // Third column's norm squared
|
double gamma = m13*m13+m23*m23+m33*m33; // Third column's norm squared
|
||||||
alpha = 1.0 - 0.5*(alpha-1.0); // Get mult. factor
|
alpha = 1.0 - 0.5*(alpha-1.0); // Get mult. factor
|
||||||
beta = 1.0 - 0.5*(beta-1.0);
|
beta = 1.0 - 0.5*(beta-1.0);
|
||||||
gamma = 1.0 - 0.5*(gamma-1.0);
|
gamma = 1.0 - 0.5*(gamma-1.0);
|
||||||
@@ -236,7 +236,7 @@ Matrix3x4& Matrix3x4::ReNormalize() // Re-normalizes nearly orthonormal matrix
|
|||||||
alpha *= 0.5;
|
alpha *= 0.5;
|
||||||
beta *= 0.5;
|
beta *= 0.5;
|
||||||
gamma *= 0.5;
|
gamma *= 0.5;
|
||||||
register double temp1, temp2;
|
double temp1, temp2;
|
||||||
temp1 = m11-alpha*m12-beta*m13; // Update row1
|
temp1 = m11-alpha*m12-beta*m13; // Update row1
|
||||||
temp2 = m12-alpha*m11-gamma*m13;
|
temp2 = m12-alpha*m11-gamma*m13;
|
||||||
m13 -= beta*m11+gamma*m12;
|
m13 -= beta*m11+gamma*m12;
|
||||||
@@ -340,7 +340,7 @@ LinearMapR3 LinearMapR3::Inverse() const // Returns inverse
|
|||||||
double sd23 = m31*m12-m11*m32;
|
double sd23 = m31*m12-m11*m32;
|
||||||
double sd33 = m11*m22-m21*m12;
|
double sd33 = m11*m22-m21*m12;
|
||||||
|
|
||||||
register double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13);
|
double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13);
|
||||||
|
|
||||||
return( LinearMapR3( sd11*detInv, sd12*detInv, sd13*detInv,
|
return( LinearMapR3( sd11*detInv, sd12*detInv, sd13*detInv,
|
||||||
sd21*detInv, sd22*detInv, sd23*detInv,
|
sd21*detInv, sd22*detInv, sd23*detInv,
|
||||||
@@ -359,7 +359,7 @@ LinearMapR3& LinearMapR3::Invert() // Converts into inverse.
|
|||||||
double sd23 = m31*m12-m11*m32;
|
double sd23 = m31*m12-m11*m32;
|
||||||
double sd33 = m11*m22-m21*m12;
|
double sd33 = m11*m22-m21*m12;
|
||||||
|
|
||||||
register double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13);
|
double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13);
|
||||||
|
|
||||||
m11 = sd11*detInv;
|
m11 = sd11*detInv;
|
||||||
m12 = sd21*detInv;
|
m12 = sd21*detInv;
|
||||||
@@ -441,7 +441,7 @@ AffineMapR3 AffineMapR3::Inverse() const // Returns inverse
|
|||||||
double sd23 = m31*m12-m11*m32;
|
double sd23 = m31*m12-m11*m32;
|
||||||
double sd33 = m11*m22-m21*m12;
|
double sd33 = m11*m22-m21*m12;
|
||||||
|
|
||||||
register double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13);
|
double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13);
|
||||||
|
|
||||||
// Make sd's hold the (transpose of) the inverse of the 3x3 part
|
// Make sd's hold the (transpose of) the inverse of the 3x3 part
|
||||||
sd11 *= detInv;
|
sd11 *= detInv;
|
||||||
@@ -475,7 +475,7 @@ AffineMapR3& AffineMapR3::Invert() // Converts into inverse.
|
|||||||
double sd23 = m31*m12-m11*m32;
|
double sd23 = m31*m12-m11*m32;
|
||||||
double sd33 = m11*m22-m21*m12;
|
double sd33 = m11*m22-m21*m12;
|
||||||
|
|
||||||
register double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13);
|
double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13);
|
||||||
|
|
||||||
m11 = sd11*detInv;
|
m11 = sd11*detInv;
|
||||||
m12 = sd21*detInv;
|
m12 = sd21*detInv;
|
||||||
@@ -541,9 +541,9 @@ RotationMapR3& RotationMapR3::Set( const Quaternion& quat )
|
|||||||
RotationMapR3& RotationMapR3::Set( const VectorR3& u, double theta )
|
RotationMapR3& RotationMapR3::Set( const VectorR3& u, double theta )
|
||||||
{
|
{
|
||||||
assert ( fabs(u.NormSq()-1.0)<2.0e-6 );
|
assert ( fabs(u.NormSq()-1.0)<2.0e-6 );
|
||||||
register double c = cos(theta);
|
double c = cos(theta);
|
||||||
register double s = sin(theta);
|
double s = sin(theta);
|
||||||
register double mc = 1.0-c;
|
double mc = 1.0-c;
|
||||||
double xmc = u.x*mc;
|
double xmc = u.x*mc;
|
||||||
double xymc = xmc*u.y;
|
double xymc = xmc*u.y;
|
||||||
double xzmc = xmc*u.z;
|
double xzmc = xmc*u.z;
|
||||||
@@ -673,9 +673,9 @@ RotationMapR3 RotateToMap( const VectorR3& fromVec, const VectorR3& toVec)
|
|||||||
RigidMapR3& RigidMapR3::SetRotationPart( const VectorR3& u, double theta )
|
RigidMapR3& RigidMapR3::SetRotationPart( const VectorR3& u, double theta )
|
||||||
{
|
{
|
||||||
assert ( fabs(u.NormSq()-1.0)<2.0e-6 );
|
assert ( fabs(u.NormSq()-1.0)<2.0e-6 );
|
||||||
register double c = cos(theta);
|
double c = cos(theta);
|
||||||
register double s = sin(theta);
|
double s = sin(theta);
|
||||||
register double mc = 1.0-c;
|
double mc = 1.0-c;
|
||||||
double xmc = u.x*mc;
|
double xmc = u.x*mc;
|
||||||
double xymc = xmc*u.y;
|
double xymc = xmc*u.y;
|
||||||
double xzmc = xmc*u.z;
|
double xzmc = xmc*u.z;
|
||||||
|
|||||||
@@ -110,7 +110,7 @@ public:
|
|||||||
VectorR3& operator*= ( double m )
|
VectorR3& operator*= ( double m )
|
||||||
{ x*=m; y*=m; z*=m; return(*this); }
|
{ x*=m; y*=m; z*=m; return(*this); }
|
||||||
VectorR3& operator/= ( double m )
|
VectorR3& operator/= ( double m )
|
||||||
{ register double mInv = 1.0/m;
|
{ double mInv = 1.0/m;
|
||||||
x*=mInv; y*=mInv; z*=mInv;
|
x*=mInv; y*=mInv; z*=mInv;
|
||||||
return(*this); }
|
return(*this); }
|
||||||
VectorR3 operator- () const { return ( VectorR3(-x, -y, -z) ); }
|
VectorR3 operator- () const { return ( VectorR3(-x, -y, -z) ); }
|
||||||
@@ -130,10 +130,10 @@ public:
|
|||||||
inline VectorR3& MakeUnit(); // Normalize() with error checking
|
inline VectorR3& MakeUnit(); // Normalize() with error checking
|
||||||
inline VectorR3& ReNormalize();
|
inline VectorR3& ReNormalize();
|
||||||
bool IsUnit( ) const
|
bool IsUnit( ) const
|
||||||
{ register double norm = Norm();
|
{ double norm = Norm();
|
||||||
return ( 1.000001>=norm && norm>=0.999999 ); }
|
return ( 1.000001>=norm && norm>=0.999999 ); }
|
||||||
bool IsUnit( double tolerance ) const
|
bool IsUnit( double tolerance ) const
|
||||||
{ register double norm = Norm();
|
{ double norm = Norm();
|
||||||
return ( 1.0+tolerance>=norm && norm>=1.0-tolerance ); }
|
return ( 1.0+tolerance>=norm && norm>=1.0-tolerance ); }
|
||||||
bool NearZero(double tolerance) const { return( MaxAbs()<=tolerance );}
|
bool NearZero(double tolerance) const { return( MaxAbs()<=tolerance );}
|
||||||
// tolerance should be non-negative
|
// tolerance should be non-negative
|
||||||
@@ -646,17 +646,17 @@ inline VectorR3 operator-( const VectorR3& u, const VectorR3& v )
|
|||||||
{
|
{
|
||||||
return VectorR3(u.x-v.x, u.y-v.y, u.z-v.z);
|
return VectorR3(u.x-v.x, u.y-v.y, u.z-v.z);
|
||||||
}
|
}
|
||||||
inline VectorR3 operator*( const VectorR3& u, register double m)
|
inline VectorR3 operator*( const VectorR3& u, double m)
|
||||||
{
|
{
|
||||||
return VectorR3( u.x*m, u.y*m, u.z*m);
|
return VectorR3( u.x*m, u.y*m, u.z*m);
|
||||||
}
|
}
|
||||||
inline VectorR3 operator*( register double m, const VectorR3& u)
|
inline VectorR3 operator*( double m, const VectorR3& u)
|
||||||
{
|
{
|
||||||
return VectorR3( u.x*m, u.y*m, u.z*m);
|
return VectorR3( u.x*m, u.y*m, u.z*m);
|
||||||
}
|
}
|
||||||
inline VectorR3 operator/( const VectorR3& u, double m)
|
inline VectorR3 operator/( const VectorR3& u, double m)
|
||||||
{
|
{
|
||||||
register double mInv = 1.0/m;
|
double mInv = 1.0/m;
|
||||||
return VectorR3( u.x*mInv, u.y*mInv, u.z*mInv);
|
return VectorR3( u.x*mInv, u.y*mInv, u.z*mInv);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -716,14 +716,14 @@ inline VectorR3::VectorR3( const VectorHgR3& uH )
|
|||||||
inline VectorR3& VectorR3::ReNormalize() // Convert near unit back to unit
|
inline VectorR3& VectorR3::ReNormalize() // Convert near unit back to unit
|
||||||
{
|
{
|
||||||
double nSq = NormSq();
|
double nSq = NormSq();
|
||||||
register double mFact = 1.0-0.5*(nSq-1.0); // Multiplicative factor
|
double mFact = 1.0-0.5*(nSq-1.0); // Multiplicative factor
|
||||||
*this *= mFact;
|
*this *= mFact;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline double NormalizeError (const VectorR3& u)
|
inline double NormalizeError (const VectorR3& u)
|
||||||
{
|
{
|
||||||
register double discrepancy;
|
double discrepancy;
|
||||||
discrepancy = u.x*u.x + u.y*u.y + u.z*u.z - 1.0;
|
discrepancy = u.x*u.x + u.y*u.y + u.z*u.z - 1.0;
|
||||||
if ( discrepancy < 0.0 ) {
|
if ( discrepancy < 0.0 ) {
|
||||||
discrepancy = -discrepancy;
|
discrepancy = -discrepancy;
|
||||||
@@ -1000,7 +1000,7 @@ inline double Matrix3x3::Diagonal( int i )
|
|||||||
|
|
||||||
inline void Matrix3x3::MakeTranspose() // Transposes it.
|
inline void Matrix3x3::MakeTranspose() // Transposes it.
|
||||||
{
|
{
|
||||||
register double temp;
|
double temp;
|
||||||
temp = m12;
|
temp = m12;
|
||||||
m12 = m21;
|
m12 = m21;
|
||||||
m21=temp;
|
m21=temp;
|
||||||
@@ -1515,7 +1515,7 @@ inline LinearMapR3 operator- (const LinearMapR3& A, const Matrix3x3& B)
|
|||||||
A.m13-B.m13, A.m23-B.m23, A.m33-B.m33 ) );
|
A.m13-B.m13, A.m23-B.m23, A.m33-B.m33 ) );
|
||||||
}
|
}
|
||||||
|
|
||||||
inline LinearMapR3& LinearMapR3::operator*= (register double b)
|
inline LinearMapR3& LinearMapR3::operator*= ( double b)
|
||||||
{
|
{
|
||||||
m11 *= b;
|
m11 *= b;
|
||||||
m12 *= b;
|
m12 *= b;
|
||||||
@@ -1529,14 +1529,14 @@ inline LinearMapR3& LinearMapR3::operator*= (register double b)
|
|||||||
return ( *this);
|
return ( *this);
|
||||||
}
|
}
|
||||||
|
|
||||||
inline LinearMapR3 operator* ( const LinearMapR3& A, register double b)
|
inline LinearMapR3 operator* ( const LinearMapR3& A, double b)
|
||||||
{
|
{
|
||||||
return( LinearMapR3( A.m11*b, A.m21*b, A.m31*b,
|
return( LinearMapR3( A.m11*b, A.m21*b, A.m31*b,
|
||||||
A.m12*b, A.m22*b, A.m32*b,
|
A.m12*b, A.m22*b, A.m32*b,
|
||||||
A.m13*b, A.m23*b, A.m33*b ) );
|
A.m13*b, A.m23*b, A.m33*b ) );
|
||||||
}
|
}
|
||||||
|
|
||||||
inline LinearMapR3 operator* ( register double b, const LinearMapR3& A)
|
inline LinearMapR3 operator* ( double b, const LinearMapR3& A)
|
||||||
{
|
{
|
||||||
return( LinearMapR3( A.m11*b, A.m21*b, A.m31*b,
|
return( LinearMapR3( A.m11*b, A.m21*b, A.m31*b,
|
||||||
A.m12*b, A.m22*b, A.m32*b,
|
A.m12*b, A.m22*b, A.m32*b,
|
||||||
@@ -1545,15 +1545,15 @@ inline LinearMapR3 operator* ( register double b, const LinearMapR3& A)
|
|||||||
|
|
||||||
inline LinearMapR3 operator/ ( const LinearMapR3& A, double b)
|
inline LinearMapR3 operator/ ( const LinearMapR3& A, double b)
|
||||||
{
|
{
|
||||||
register double bInv = 1.0/b;
|
double bInv = 1.0/b;
|
||||||
return( LinearMapR3( A.m11*bInv, A.m21*bInv, A.m31*bInv,
|
return( LinearMapR3( A.m11*bInv, A.m21*bInv, A.m31*bInv,
|
||||||
A.m12*bInv, A.m22*bInv, A.m32*bInv,
|
A.m12*bInv, A.m22*bInv, A.m32*bInv,
|
||||||
A.m13*bInv, A.m23*bInv, A.m33*bInv ) );
|
A.m13*bInv, A.m23*bInv, A.m33*bInv ) );
|
||||||
}
|
}
|
||||||
|
|
||||||
inline LinearMapR3& LinearMapR3::operator/= (register double b)
|
inline LinearMapR3& LinearMapR3::operator/= ( double b)
|
||||||
{
|
{
|
||||||
register double bInv = 1.0/b;
|
double bInv = 1.0/b;
|
||||||
return ( *this *= bInv );
|
return ( *this *= bInv );
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -1730,7 +1730,7 @@ inline AffineMapR3 operator- (const LinearMapR3& B, const AffineMapR3& A)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
inline AffineMapR3& AffineMapR3::operator*= (register double b)
|
inline AffineMapR3& AffineMapR3::operator*= ( double b)
|
||||||
{
|
{
|
||||||
m11 *= b;
|
m11 *= b;
|
||||||
m12 *= b;
|
m12 *= b;
|
||||||
@@ -1747,7 +1747,7 @@ inline AffineMapR3& AffineMapR3::operator*= (register double b)
|
|||||||
return (*this);
|
return (*this);
|
||||||
}
|
}
|
||||||
|
|
||||||
inline AffineMapR3 operator* (const AffineMapR3& A, register double b)
|
inline AffineMapR3 operator* (const AffineMapR3& A, double b)
|
||||||
{
|
{
|
||||||
return(AffineMapR3( A.m11*b, A.m21*b, A.m31*b,
|
return(AffineMapR3( A.m11*b, A.m21*b, A.m31*b,
|
||||||
A.m12*b, A.m22*b, A.m32*b,
|
A.m12*b, A.m22*b, A.m32*b,
|
||||||
@@ -1755,7 +1755,7 @@ inline AffineMapR3 operator* (const AffineMapR3& A, register double b)
|
|||||||
A.m14*b, A.m24*b, A.m34*b ) );
|
A.m14*b, A.m24*b, A.m34*b ) );
|
||||||
}
|
}
|
||||||
|
|
||||||
inline AffineMapR3 operator* (register double b, const AffineMapR3& A)
|
inline AffineMapR3 operator* ( double b, const AffineMapR3& A)
|
||||||
{
|
{
|
||||||
return(AffineMapR3( A.m11*b, A.m21*b, A.m31*b,
|
return(AffineMapR3( A.m11*b, A.m21*b, A.m31*b,
|
||||||
A.m12*b, A.m22*b, A.m32*b,
|
A.m12*b, A.m22*b, A.m32*b,
|
||||||
@@ -1765,14 +1765,14 @@ inline AffineMapR3 operator* (register double b, const AffineMapR3& A)
|
|||||||
|
|
||||||
inline AffineMapR3& AffineMapR3::operator/= (double b)
|
inline AffineMapR3& AffineMapR3::operator/= (double b)
|
||||||
{
|
{
|
||||||
register double bInv = 1.0/b;
|
double bInv = 1.0/b;
|
||||||
*this *= bInv;
|
*this *= bInv;
|
||||||
return( *this );
|
return( *this );
|
||||||
}
|
}
|
||||||
|
|
||||||
inline AffineMapR3 operator/ (const AffineMapR3& A, double b)
|
inline AffineMapR3 operator/ (const AffineMapR3& A, double b)
|
||||||
{
|
{
|
||||||
register double bInv = 1.0/b;
|
double bInv = 1.0/b;
|
||||||
return(AffineMapR3( A.m11*bInv, A.m21*bInv, A.m31*bInv,
|
return(AffineMapR3( A.m11*bInv, A.m21*bInv, A.m31*bInv,
|
||||||
A.m12*bInv, A.m22*bInv, A.m32*bInv,
|
A.m12*bInv, A.m22*bInv, A.m32*bInv,
|
||||||
A.m13*bInv, A.m23*bInv, A.m33*bInv,
|
A.m13*bInv, A.m23*bInv, A.m33*bInv,
|
||||||
@@ -1823,7 +1823,7 @@ inline RotationMapR3 RotationMapR3::Inverse() const // Returns inverse
|
|||||||
|
|
||||||
inline RotationMapR3& RotationMapR3::Invert() // Converts into inverse.
|
inline RotationMapR3& RotationMapR3::Invert() // Converts into inverse.
|
||||||
{
|
{
|
||||||
register double temp;
|
double temp;
|
||||||
temp = m12;
|
temp = m12;
|
||||||
m12 = m21;
|
m12 = m21;
|
||||||
m21 = temp;
|
m21 = temp;
|
||||||
@@ -1934,7 +1934,7 @@ inline RigidMapR3& RigidMapR3::Invert() // Converts into inverse.
|
|||||||
m14 = new14;
|
m14 = new14;
|
||||||
m24 = new24;
|
m24 = new24;
|
||||||
|
|
||||||
register double temp;
|
double temp;
|
||||||
temp = m12;
|
temp = m12;
|
||||||
m12 = m21;
|
m12 = m21;
|
||||||
m21 = temp;
|
m21 = temp;
|
||||||
|
|||||||
@@ -45,7 +45,7 @@ const Matrix4x4 Matrix4x4::Identity(1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0,
|
|||||||
|
|
||||||
double VectorR4::MaxAbs() const
|
double VectorR4::MaxAbs() const
|
||||||
{
|
{
|
||||||
register double m;
|
double m;
|
||||||
m = (x>0.0) ? x : -x;
|
m = (x>0.0) ? x : -x;
|
||||||
if ( y>m ) m=y;
|
if ( y>m ) m=y;
|
||||||
else if ( -y >m ) m = -y;
|
else if ( -y >m ) m = -y;
|
||||||
@@ -99,7 +99,7 @@ void Matrix4x4::operator*= (const Matrix4x4& B) // Matrix product
|
|||||||
|
|
||||||
inline void ReNormalizeHelper ( double &a, double &b, double &c, double &d )
|
inline void ReNormalizeHelper ( double &a, double &b, double &c, double &d )
|
||||||
{
|
{
|
||||||
register double scaleF = a*a+b*b+c*c+d*d; // Inner product of Vector-R4
|
double scaleF = a*a+b*b+c*c+d*d; // Inner product of Vector-R4
|
||||||
scaleF = 1.0-0.5*(scaleF-1.0);
|
scaleF = 1.0-0.5*(scaleF-1.0);
|
||||||
a *= scaleF;
|
a *= scaleF;
|
||||||
b *= scaleF;
|
b *= scaleF;
|
||||||
@@ -212,7 +212,7 @@ LinearMapR4 LinearMapR4::Inverse() const // Returns inverse
|
|||||||
double sd44 = m11*Tbt23C23 - m12*Tbt23C13 + m13*Tbt23C12;
|
double sd44 = m11*Tbt23C23 - m12*Tbt23C13 + m13*Tbt23C12;
|
||||||
|
|
||||||
|
|
||||||
register double detInv = 1.0/(m11*sd11 - m12*sd12 + m13*sd13 - m14*sd14);
|
double detInv = 1.0/(m11*sd11 - m12*sd12 + m13*sd13 - m14*sd14);
|
||||||
|
|
||||||
return( LinearMapR4( sd11*detInv, -sd12*detInv, sd13*detInv, -sd14*detInv,
|
return( LinearMapR4( sd11*detInv, -sd12*detInv, sd13*detInv, -sd14*detInv,
|
||||||
-sd21*detInv, sd22*detInv, -sd23*detInv, sd24*detInv,
|
-sd21*detInv, sd22*detInv, -sd23*detInv, sd24*detInv,
|
||||||
@@ -258,7 +258,7 @@ LinearMapR4& LinearMapR4::Invert() // Converts into inverse.
|
|||||||
double sd43 = m11*Tbt23C24 - m12*Tbt23C14 + m14*Tbt23C12;
|
double sd43 = m11*Tbt23C24 - m12*Tbt23C14 + m14*Tbt23C12;
|
||||||
double sd44 = m11*Tbt23C23 - m12*Tbt23C13 + m13*Tbt23C12;
|
double sd44 = m11*Tbt23C23 - m12*Tbt23C13 + m13*Tbt23C12;
|
||||||
|
|
||||||
register double detInv = 1.0/(m11*sd11 - m12*sd12 + m13*sd13 - m14*sd14);
|
double detInv = 1.0/(m11*sd11 - m12*sd12 + m13*sd13 - m14*sd14);
|
||||||
|
|
||||||
m11 = sd11*detInv;
|
m11 = sd11*detInv;
|
||||||
m12 = -sd21*detInv;
|
m12 = -sd21*detInv;
|
||||||
|
|||||||
@@ -91,7 +91,7 @@ public:
|
|||||||
VectorR4& operator*= ( double m )
|
VectorR4& operator*= ( double m )
|
||||||
{ x*=m; y*=m; z*=m; w*=m; return(*this); }
|
{ x*=m; y*=m; z*=m; w*=m; return(*this); }
|
||||||
VectorR4& operator/= ( double m )
|
VectorR4& operator/= ( double m )
|
||||||
{ register double mInv = 1.0/m;
|
{ double mInv = 1.0/m;
|
||||||
x*=mInv; y*=mInv; z*=mInv; w*=mInv;
|
x*=mInv; y*=mInv; z*=mInv; w*=mInv;
|
||||||
return(*this); }
|
return(*this); }
|
||||||
VectorR4 operator- () const { return ( VectorR4(-x, -y, -z, -w) ); }
|
VectorR4 operator- () const { return ( VectorR4(-x, -y, -z, -w) ); }
|
||||||
@@ -109,10 +109,10 @@ public:
|
|||||||
inline VectorR4& MakeUnit(); // Normalize() with error checking
|
inline VectorR4& MakeUnit(); // Normalize() with error checking
|
||||||
inline VectorR4& ReNormalize();
|
inline VectorR4& ReNormalize();
|
||||||
bool IsUnit( ) const
|
bool IsUnit( ) const
|
||||||
{ register double norm = Norm();
|
{ double norm = Norm();
|
||||||
return ( 1.000001>=norm && norm>=0.999999 ); }
|
return ( 1.000001>=norm && norm>=0.999999 ); }
|
||||||
bool IsUnit( double tolerance ) const
|
bool IsUnit( double tolerance ) const
|
||||||
{ register double norm = Norm();
|
{ double norm = Norm();
|
||||||
return ( 1.0+tolerance>=norm && norm>=1.0-tolerance ); }
|
return ( 1.0+tolerance>=norm && norm>=1.0-tolerance ); }
|
||||||
bool IsZero() const { return ( x==0.0 && y==0.0 && z==0.0 && w==0.0); }
|
bool IsZero() const { return ( x==0.0 && y==0.0 && z==0.0 && w==0.0); }
|
||||||
bool NearZero(double tolerance) const { return( MaxAbs()<=tolerance );}
|
bool NearZero(double tolerance) const { return( MaxAbs()<=tolerance );}
|
||||||
@@ -428,17 +428,17 @@ inline VectorR4 operator-( const VectorR4& u, const VectorR4& v )
|
|||||||
{
|
{
|
||||||
return VectorR4(u.x-v.x, u.y-v.y, u.z-v.z, u.w-v.w);
|
return VectorR4(u.x-v.x, u.y-v.y, u.z-v.z, u.w-v.w);
|
||||||
}
|
}
|
||||||
inline VectorR4 operator*( const VectorR4& u, register double m)
|
inline VectorR4 operator*( const VectorR4& u, double m)
|
||||||
{
|
{
|
||||||
return VectorR4( u.x*m, u.y*m, u.z*m, u.w*m );
|
return VectorR4( u.x*m, u.y*m, u.z*m, u.w*m );
|
||||||
}
|
}
|
||||||
inline VectorR4 operator*( register double m, const VectorR4& u)
|
inline VectorR4 operator*( double m, const VectorR4& u)
|
||||||
{
|
{
|
||||||
return VectorR4( u.x*m, u.y*m, u.z*m, u.w*m );
|
return VectorR4( u.x*m, u.y*m, u.z*m, u.w*m );
|
||||||
}
|
}
|
||||||
inline VectorR4 operator/( const VectorR4& u, double m)
|
inline VectorR4 operator/( const VectorR4& u, double m)
|
||||||
{
|
{
|
||||||
register double mInv = 1.0/m;
|
double mInv = 1.0/m;
|
||||||
return VectorR4( u.x*mInv, u.y*mInv, u.z*mInv, u.w*mInv );
|
return VectorR4( u.x*mInv, u.y*mInv, u.z*mInv, u.w*mInv );
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -486,14 +486,14 @@ inline VectorR4& VectorR4::AddScaled( const VectorR4& u, double s )
|
|||||||
inline VectorR4& VectorR4::ReNormalize() // Convert near unit back to unit
|
inline VectorR4& VectorR4::ReNormalize() // Convert near unit back to unit
|
||||||
{
|
{
|
||||||
double nSq = NormSq();
|
double nSq = NormSq();
|
||||||
register double mFact = 1.0-0.5*(nSq-1.0); // Multiplicative factor
|
double mFact = 1.0-0.5*(nSq-1.0); // Multiplicative factor
|
||||||
*this *= mFact;
|
*this *= mFact;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline double NormalizeError (const VectorR4& u)
|
inline double NormalizeError (const VectorR4& u)
|
||||||
{
|
{
|
||||||
register double discrepancy;
|
double discrepancy;
|
||||||
discrepancy = u.x*u.x + u.y*u.y + u.z*u.z + u.w*u.w - 1.0;
|
discrepancy = u.x*u.x + u.y*u.y + u.z*u.z + u.w*u.w - 1.0;
|
||||||
if ( discrepancy < 0.0 ) {
|
if ( discrepancy < 0.0 ) {
|
||||||
discrepancy = -discrepancy;
|
discrepancy = -discrepancy;
|
||||||
@@ -796,7 +796,7 @@ inline double Matrix4x4::Diagonal( int i )
|
|||||||
|
|
||||||
inline void Matrix4x4::MakeTranspose() // Transposes it.
|
inline void Matrix4x4::MakeTranspose() // Transposes it.
|
||||||
{
|
{
|
||||||
register double temp;
|
double temp;
|
||||||
temp = m12;
|
temp = m12;
|
||||||
m12 = m21;
|
m12 = m21;
|
||||||
m21=temp;
|
m21=temp;
|
||||||
@@ -924,7 +924,7 @@ inline LinearMapR4 operator- (const LinearMapR4& A, const LinearMapR4& B)
|
|||||||
A.m14-B.m14, A.m24-B.m24, A.m34-B.m34, A.m44-B.m44 ) );
|
A.m14-B.m14, A.m24-B.m24, A.m34-B.m34, A.m44-B.m44 ) );
|
||||||
}
|
}
|
||||||
|
|
||||||
inline LinearMapR4& LinearMapR4::operator*= (register double b)
|
inline LinearMapR4& LinearMapR4::operator*= ( double b)
|
||||||
{
|
{
|
||||||
m11 *= b;
|
m11 *= b;
|
||||||
m12 *= b;
|
m12 *= b;
|
||||||
@@ -945,7 +945,7 @@ inline LinearMapR4& LinearMapR4::operator*= (register double b)
|
|||||||
return ( *this);
|
return ( *this);
|
||||||
}
|
}
|
||||||
|
|
||||||
inline LinearMapR4 operator* ( const LinearMapR4& A, register double b)
|
inline LinearMapR4 operator* ( const LinearMapR4& A, double b)
|
||||||
{
|
{
|
||||||
return( LinearMapR4( A.m11*b, A.m21*b, A.m31*b, A.m41*b,
|
return( LinearMapR4( A.m11*b, A.m21*b, A.m31*b, A.m41*b,
|
||||||
A.m12*b, A.m22*b, A.m32*b, A.m42*b,
|
A.m12*b, A.m22*b, A.m32*b, A.m42*b,
|
||||||
@@ -953,7 +953,7 @@ inline LinearMapR4 operator* ( const LinearMapR4& A, register double b)
|
|||||||
A.m14*b, A.m24*b, A.m34*b, A.m44*b) );
|
A.m14*b, A.m24*b, A.m34*b, A.m44*b) );
|
||||||
}
|
}
|
||||||
|
|
||||||
inline LinearMapR4 operator* ( register double b, const LinearMapR4& A)
|
inline LinearMapR4 operator* ( double b, const LinearMapR4& A)
|
||||||
{
|
{
|
||||||
return( LinearMapR4( A.m11*b, A.m21*b, A.m31*b, A.m41*b,
|
return( LinearMapR4( A.m11*b, A.m21*b, A.m31*b, A.m41*b,
|
||||||
A.m12*b, A.m22*b, A.m32*b, A.m42*b,
|
A.m12*b, A.m22*b, A.m32*b, A.m42*b,
|
||||||
@@ -963,13 +963,13 @@ inline LinearMapR4 operator* ( register double b, const LinearMapR4& A)
|
|||||||
|
|
||||||
inline LinearMapR4 operator/ ( const LinearMapR4& A, double b)
|
inline LinearMapR4 operator/ ( const LinearMapR4& A, double b)
|
||||||
{
|
{
|
||||||
register double bInv = 1.0/b;
|
double bInv = 1.0/b;
|
||||||
return ( A*bInv );
|
return ( A*bInv );
|
||||||
}
|
}
|
||||||
|
|
||||||
inline LinearMapR4& LinearMapR4::operator/= (register double b)
|
inline LinearMapR4& LinearMapR4::operator/= ( double b)
|
||||||
{
|
{
|
||||||
register double bInv = 1.0/b;
|
double bInv = 1.0/b;
|
||||||
return ( *this *= bInv );
|
return ( *this *= bInv );
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -182,7 +182,7 @@ void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zb
|
|||||||
bool discard = shader.fragment(bc_clip, color);
|
bool discard = shader.fragment(bc_clip, color);
|
||||||
if (frag_depth<-shader.m_farPlane)
|
if (frag_depth<-shader.m_farPlane)
|
||||||
discard=true;
|
discard=true;
|
||||||
if (frag_depth>-shader.m_nearPlane)
|
if (frag_depth>shader.m_nearPlane)
|
||||||
discard=true;
|
discard=true;
|
||||||
|
|
||||||
if (!discard) {
|
if (!discard) {
|
||||||
|
|||||||
45
examples/pybullet/examples/frictionCone.py
Normal file
45
examples/pybullet/examples/frictionCone.py
Normal file
@@ -0,0 +1,45 @@
|
|||||||
|
import pybullet as p
|
||||||
|
import time
|
||||||
|
import math
|
||||||
|
|
||||||
|
p.connect(p.GUI)
|
||||||
|
useMaximalCoordinates = False
|
||||||
|
|
||||||
|
p.setGravity(0,0,-10)
|
||||||
|
plane=p.loadURDF("plane.urdf",[0,0,-1],useMaximalCoordinates=useMaximalCoordinates)
|
||||||
|
|
||||||
|
p.setRealTimeSimulation(0)
|
||||||
|
|
||||||
|
|
||||||
|
velocity = 1
|
||||||
|
num = 40
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)#disable this to make it faster
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER,0)
|
||||||
|
|
||||||
|
for i in range (num):
|
||||||
|
print("progress:",i,num)
|
||||||
|
|
||||||
|
x = velocity*math.sin(2.*3.1415*float(i)/num)
|
||||||
|
y = velocity*math.cos(2.*3.1415*float(i)/num)
|
||||||
|
print("velocity=",x,y)
|
||||||
|
sphere=p.loadURDF("sphere_small_zeroinertia.urdf", flags=p.URDF_USE_INERTIA_FROM_FILE, useMaximalCoordinates=useMaximalCoordinates)
|
||||||
|
p.changeDynamics(sphere,-1,lateralFriction=0.02)
|
||||||
|
#p.changeDynamics(sphere,-1,rollingFriction=10)
|
||||||
|
p.changeDynamics(sphere,-1,linearDamping=0)
|
||||||
|
p.changeDynamics(sphere,-1,angularDamping=0)
|
||||||
|
p.resetBaseVelocity(sphere,linearVelocity=[x,y,0])
|
||||||
|
|
||||||
|
prevPos = [0,0,0]
|
||||||
|
for i in range (2048):
|
||||||
|
p.stepSimulation()
|
||||||
|
pos = p.getBasePositionAndOrientation(sphere)[0]
|
||||||
|
if (i&64):
|
||||||
|
p.addUserDebugLine(prevPos,pos,[1,0,0],1)
|
||||||
|
prevPos = pos
|
||||||
|
|
||||||
|
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||||
|
|
||||||
|
|
||||||
|
while (1):
|
||||||
|
time.sleep(0.01)
|
||||||
12
examples/pybullet/examples/motorMaxVelocity.py
Normal file
12
examples/pybullet/examples/motorMaxVelocity.py
Normal file
@@ -0,0 +1,12 @@
|
|||||||
|
import pybullet as p
|
||||||
|
import time
|
||||||
|
|
||||||
|
p.connect(p.GUI)
|
||||||
|
cartpole=p.loadURDF("cartpole.urdf")
|
||||||
|
p.setRealTimeSimulation(1)
|
||||||
|
p.setJointMotorControl2(cartpole,1,p.POSITION_CONTROL,targetPosition=1000,targetVelocity=0,force=1000, positionGain=1, velocityGain=0, maxVelocity=0.5)
|
||||||
|
while (1):
|
||||||
|
p.setGravity(0,0,-10)
|
||||||
|
js = p.getJointState(cartpole,1)
|
||||||
|
print("position=",js[0],"velocity=",js[1])
|
||||||
|
time.sleep(0.01)
|
||||||
@@ -1,48 +1,70 @@
|
|||||||
import numpy as np
|
|
||||||
|
#testrender.py is a bit slower than testrender_np.py: pixels are copied from C to Python one by one
|
||||||
|
|
||||||
|
|
||||||
import matplotlib.pyplot as plt
|
import matplotlib.pyplot as plt
|
||||||
import pybullet
|
import pybullet
|
||||||
|
import time
|
||||||
|
|
||||||
pybullet.connect(pybullet.GUI)
|
plt.ion()
|
||||||
pybullet.loadURDF("plane.urdf")
|
|
||||||
|
img = [[1,2,3]*50]*100#np.random.rand(200, 320)
|
||||||
|
#img = [tandard_normal((50,100))
|
||||||
|
image = plt.imshow(img,interpolation='none',animated=True,label="blah")
|
||||||
|
ax = plt.gca()
|
||||||
|
|
||||||
|
|
||||||
|
pybullet.connect(pybullet.DIRECT)
|
||||||
|
pybullet.loadURDF("plane.urdf",[0,0,-1])
|
||||||
pybullet.loadURDF("r2d2.urdf")
|
pybullet.loadURDF("r2d2.urdf")
|
||||||
|
|
||||||
camTargetPos = [0.,0.,0.]
|
pybullet.setGravity(0,0,-10)
|
||||||
|
camTargetPos = [0,0,0]
|
||||||
cameraUp = [0,0,1]
|
cameraUp = [0,0,1]
|
||||||
cameraPos = [1,1,1]
|
cameraPos = [1,1,1]
|
||||||
yaw = 40
|
|
||||||
pitch = 10.0
|
pitch = -10.0
|
||||||
|
|
||||||
roll=0
|
roll=0
|
||||||
upAxisIndex = 2
|
upAxisIndex = 2
|
||||||
camDistance = 4
|
camDistance = 4
|
||||||
pixelWidth = 320
|
pixelWidth = 320
|
||||||
pixelHeight = 240
|
pixelHeight = 200
|
||||||
nearPlane = 0.01
|
nearPlane = 0.01
|
||||||
farPlane = 1000
|
farPlane = 100
|
||||||
lightDirection = [0.4,0.4,0]
|
|
||||||
lightColor = [.3,.3,.3]#1,1,1]#optional argument
|
|
||||||
fov = 60
|
fov = 60
|
||||||
|
|
||||||
#img_arr = pybullet.renderImage(pixelWidth, pixelHeight)
|
main_start = time.time()
|
||||||
#renderImage(w, h, view[16], projection[16])
|
while(1):
|
||||||
#img_arr = pybullet.renderImage(pixelWidth, pixelHeight, cameraPos, camTargetPos, cameraUp, nearPlane, farPlane)
|
for yaw in range (0,360,10) :
|
||||||
for pitch in range (0,360,10) :
|
pybullet.stepSimulation()
|
||||||
|
start = time.time()
|
||||||
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
|
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
|
||||||
aspect = pixelWidth / pixelHeight;
|
aspect = pixelWidth / pixelHeight;
|
||||||
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
|
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
|
||||||
#getCameraImage can also use renderer=pybullet.ER_BULLET_HARDWARE_OPENGL
|
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, shadow=1,lightDirection=[1,1,1],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
|
||||||
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, lightAmbientCoeff = 0.3, lightDiffuseCoeff = 0.4, shadow=1, renderer=pybullet.ER_TINY_RENDERER)
|
stop = time.time()
|
||||||
w=img_arr[0]
|
print ("renderImage %f" % (stop - start))
|
||||||
h=img_arr[1]
|
|
||||||
rgb=img_arr[2]
|
|
||||||
dep=img_arr[3]
|
|
||||||
#print 'width = %d height = %d' % (w,h)
|
|
||||||
# reshape creates np array
|
|
||||||
np_img_arr = np.reshape(rgb, (h, w, 4))
|
|
||||||
np_img_arr = np_img_arr*(1./255.)
|
|
||||||
#show
|
|
||||||
plt.imshow(np_img_arr,interpolation='none')
|
|
||||||
|
|
||||||
|
w=img_arr[0] #width of the image, in pixels
|
||||||
|
h=img_arr[1] #height of the image, in pixels
|
||||||
|
rgb=img_arr[2] #color data RGB
|
||||||
|
dep=img_arr[3] #depth data
|
||||||
|
#print(rgb)
|
||||||
|
print ('width = %d height = %d' % (w,h))
|
||||||
|
|
||||||
|
#note that sending the data using imshow to matplotlib is really slow, so we use set_data
|
||||||
|
|
||||||
|
#plt.imshow(rgb,interpolation='none')
|
||||||
|
image.set_data(rgb)
|
||||||
|
ax.plot([0])
|
||||||
|
#plt.draw()
|
||||||
|
#plt.show()
|
||||||
plt.pause(0.01)
|
plt.pause(0.01)
|
||||||
|
|
||||||
|
main_stop = time.time()
|
||||||
|
|
||||||
|
print ("Total time %f" % (main_stop - main_start))
|
||||||
|
|
||||||
pybullet.resetSimulation()
|
pybullet.resetSimulation()
|
||||||
|
|||||||
@@ -1,37 +1,53 @@
|
|||||||
|
|
||||||
#make sure to compile pybullet with PYBULLET_USE_NUMPY enabled, otherwise use testrender.py (slower but compatible without numpy)
|
#make sure to compile pybullet with PYBULLET_USE_NUMPY enabled
|
||||||
|
#otherwise use testrender.py (slower but compatible without numpy)
|
||||||
|
#you can also use GUI mode, for faster OpenGL rendering (instead of TinyRender CPU)
|
||||||
|
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import matplotlib.pyplot as plt
|
import matplotlib.pyplot as plt
|
||||||
import pybullet
|
import pybullet
|
||||||
import time
|
import time
|
||||||
|
|
||||||
pybullet.connect(pybullet.GUI)
|
|
||||||
|
plt.ion()
|
||||||
|
|
||||||
|
img = np.random.rand(200, 320)
|
||||||
|
#img = [tandard_normal((50,100))
|
||||||
|
image = plt.imshow(img,interpolation='none',animated=True,label="blah")
|
||||||
|
ax = plt.gca()
|
||||||
|
|
||||||
|
#pybullet.connect(pybullet.GUI)
|
||||||
|
pybullet.connect(pybullet.DIRECT)
|
||||||
|
pybullet.loadURDF("plane.urdf",[0,0,-1])
|
||||||
pybullet.loadURDF("r2d2.urdf")
|
pybullet.loadURDF("r2d2.urdf")
|
||||||
|
|
||||||
camTargetPos = [0,0,0]
|
camTargetPos = [0,0,0]
|
||||||
cameraUp = [0,0,1]
|
cameraUp = [0,0,1]
|
||||||
cameraPos = [1,1,1]
|
cameraPos = [1,1,1]
|
||||||
yaw = 40
|
pybullet.setGravity(0,0,-10)
|
||||||
pitch = 10.0
|
|
||||||
|
pitch = -10.0
|
||||||
|
|
||||||
roll=0
|
roll=0
|
||||||
upAxisIndex = 2
|
upAxisIndex = 2
|
||||||
camDistance = 4
|
camDistance = 4
|
||||||
pixelWidth = 1024
|
pixelWidth = 320
|
||||||
pixelHeight = 768
|
pixelHeight = 200
|
||||||
nearPlane = 0.01
|
nearPlane = 0.01
|
||||||
farPlane = 1000
|
farPlane = 100
|
||||||
|
|
||||||
fov = 60
|
fov = 60
|
||||||
|
|
||||||
main_start = time.time()
|
main_start = time.time()
|
||||||
for pitch in range (0,360,10) :
|
while (1):
|
||||||
|
for yaw in range (0,360,10):
|
||||||
|
pybullet.stepSimulation()
|
||||||
start = time.time()
|
start = time.time()
|
||||||
|
|
||||||
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
|
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
|
||||||
aspect = pixelWidth / pixelHeight;
|
aspect = pixelWidth / pixelHeight;
|
||||||
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
|
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
|
||||||
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, [0,1,0],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
|
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, shadow=1,lightDirection=[1,1,1],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
|
||||||
stop = time.time()
|
stop = time.time()
|
||||||
print ("renderImage %f" % (stop - start))
|
print ("renderImage %f" % (stop - start))
|
||||||
|
|
||||||
@@ -44,8 +60,21 @@ for pitch in range (0,360,10) :
|
|||||||
|
|
||||||
#note that sending the data to matplotlib is really slow
|
#note that sending the data to matplotlib is really slow
|
||||||
|
|
||||||
plt.imshow(rgb,interpolation='none')
|
#reshape is not needed
|
||||||
plt.pause(0.001)
|
#np_img_arr = np.reshape(rgb, (h, w, 4))
|
||||||
|
#np_img_arr = np_img_arr*(1./255.)
|
||||||
|
|
||||||
|
#show
|
||||||
|
#plt.imshow(np_img_arr,interpolation='none',extent=(0,1600,0,1200))
|
||||||
|
#image = plt.imshow(np_img_arr,interpolation='none',animated=True,label="blah")
|
||||||
|
|
||||||
|
image.set_data(rgb)#np_img_arr)
|
||||||
|
ax.plot([0])
|
||||||
|
#plt.draw()
|
||||||
|
#plt.show()
|
||||||
|
plt.pause(0.01)
|
||||||
|
#image.draw()
|
||||||
|
|
||||||
|
|
||||||
main_stop = time.time()
|
main_stop = time.time()
|
||||||
|
|
||||||
|
|||||||
@@ -20,4 +20,4 @@ from __future__ import print_function
|
|||||||
|
|
||||||
from . import train_ppo
|
from . import train_ppo
|
||||||
from . import utility
|
from . import utility
|
||||||
from . import visualize
|
from . import visualize_ppo
|
||||||
|
|||||||
@@ -119,6 +119,15 @@ def pybullet_racecar():
|
|||||||
return locals()
|
return locals()
|
||||||
|
|
||||||
|
|
||||||
|
def pybullet_humanoid():
|
||||||
|
locals().update(default())
|
||||||
|
randomizer = (minitaur_env_randomizer.MinitaurEnvRandomizer())
|
||||||
|
env = 'HumanoidBulletEnv-v0'
|
||||||
|
max_length = 1000
|
||||||
|
steps = 3e7 # 30M
|
||||||
|
return locals()
|
||||||
|
|
||||||
|
|
||||||
def pybullet_minitaur():
|
def pybullet_minitaur():
|
||||||
"""Configuration specific to minitaur_gym_env.MinitaurBulletEnv class."""
|
"""Configuration specific to minitaur_gym_env.MinitaurBulletEnv class."""
|
||||||
locals().update(default())
|
locals().update(default())
|
||||||
|
|||||||
@@ -1748,12 +1748,13 @@ static PyObject* pybullet_setJointMotorControl2(PyObject* self, PyObject* args,
|
|||||||
double force = 100000.0;
|
double force = 100000.0;
|
||||||
double kp = 0.1;
|
double kp = 0.1;
|
||||||
double kd = 1.0;
|
double kd = 1.0;
|
||||||
|
double maxVelocity = -1;
|
||||||
b3PhysicsClientHandle sm = 0;
|
b3PhysicsClientHandle sm = 0;
|
||||||
|
|
||||||
int physicsClientId = 0;
|
int physicsClientId = 0;
|
||||||
static char* kwlist[] = {"bodyUniqueId", "jointIndex", "controlMode", "targetPosition", "targetVelocity", "force", "positionGain", "velocityGain", "physicsClientId", NULL};
|
static char* kwlist[] = {"bodyUniqueId", "jointIndex", "controlMode", "targetPosition", "targetVelocity", "force", "positionGain", "velocityGain", "maxVelocity", "physicsClientId", NULL};
|
||||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|dddddi", kwlist, &bodyUniqueId, &jointIndex, &controlMode,
|
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|ddddddi", kwlist, &bodyUniqueId, &jointIndex, &controlMode,
|
||||||
&targetPosition, &targetVelocity, &force, &kp, &kd, &physicsClientId))
|
&targetPosition, &targetVelocity, &force, &kp, &kd, &maxVelocity, &physicsClientId))
|
||||||
{
|
{
|
||||||
//backward compatibility, bodyIndex -> bodyUniqueId, don't need to update this function: people have to migrate to bodyUniqueId
|
//backward compatibility, bodyIndex -> bodyUniqueId, don't need to update this function: people have to migrate to bodyUniqueId
|
||||||
static char* kwlist2[] = {"bodyIndex", "jointIndex", "controlMode", "targetPosition", "targetVelocity", "force", "positionGain", "velocityGain", "physicsClientId", NULL};
|
static char* kwlist2[] = {"bodyIndex", "jointIndex", "controlMode", "targetPosition", "targetVelocity", "force", "positionGain", "velocityGain", "physicsClientId", NULL};
|
||||||
@@ -1816,6 +1817,10 @@ static PyObject* pybullet_setJointMotorControl2(PyObject* self, PyObject* args,
|
|||||||
|
|
||||||
case CONTROL_MODE_POSITION_VELOCITY_PD:
|
case CONTROL_MODE_POSITION_VELOCITY_PD:
|
||||||
{
|
{
|
||||||
|
if (maxVelocity>0)
|
||||||
|
{
|
||||||
|
b3JointControlSetMaximumVelocity(commandHandle, info.m_uIndex, maxVelocity);
|
||||||
|
}
|
||||||
b3JointControlSetDesiredPosition(commandHandle, info.m_qIndex,
|
b3JointControlSetDesiredPosition(commandHandle, info.m_qIndex,
|
||||||
targetPosition);
|
targetPosition);
|
||||||
b3JointControlSetKp(commandHandle, info.m_uIndex, kp);
|
b3JointControlSetKp(commandHandle, info.m_uIndex, kp);
|
||||||
@@ -5982,7 +5987,7 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
|||||||
statusType = b3GetStatusType(statusHandle);
|
statusType = b3GetStatusType(statusHandle);
|
||||||
if (statusType == CMD_CAMERA_IMAGE_COMPLETED)
|
if (statusType == CMD_CAMERA_IMAGE_COMPLETED)
|
||||||
{
|
{
|
||||||
PyObject* item2;
|
|
||||||
PyObject* pyResultList; // store 4 elements in this result: width,
|
PyObject* pyResultList; // store 4 elements in this result: width,
|
||||||
// height, rgbData, depth
|
// height, rgbData, depth
|
||||||
|
|
||||||
@@ -5991,13 +5996,12 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
|||||||
PyObject* pyDep;
|
PyObject* pyDep;
|
||||||
PyObject* pySeg;
|
PyObject* pySeg;
|
||||||
|
|
||||||
int i, j, p;
|
int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values
|
||||||
|
|
||||||
|
|
||||||
b3GetCameraImageData(sm, &imageData);
|
b3GetCameraImageData(sm, &imageData);
|
||||||
// TODO(hellojas): error handling if image size is 0
|
// TODO(hellojas): error handling if image size is 0
|
||||||
|
{
|
||||||
int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values
|
|
||||||
|
|
||||||
npy_intp rgb_dims[3] = {imageData.m_pixelHeight, imageData.m_pixelWidth,
|
npy_intp rgb_dims[3] = {imageData.m_pixelHeight, imageData.m_pixelWidth,
|
||||||
bytesPerPixel};
|
bytesPerPixel};
|
||||||
npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth};
|
npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth};
|
||||||
@@ -6022,7 +6026,9 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
|||||||
PyTuple_SetItem(pyResultList, 2, pyRGB);
|
PyTuple_SetItem(pyResultList, 2, pyRGB);
|
||||||
PyTuple_SetItem(pyResultList, 3, pyDep);
|
PyTuple_SetItem(pyResultList, 3, pyDep);
|
||||||
PyTuple_SetItem(pyResultList, 4, pySeg);
|
PyTuple_SetItem(pyResultList, 4, pySeg);
|
||||||
|
}
|
||||||
#else //PYBULLET_USE_NUMPY
|
#else //PYBULLET_USE_NUMPY
|
||||||
|
PyObject* item2;
|
||||||
PyObject* pylistRGB;
|
PyObject* pylistRGB;
|
||||||
PyObject* pylistDep;
|
PyObject* pylistDep;
|
||||||
PyObject* pylistSeg;
|
PyObject* pylistSeg;
|
||||||
@@ -6412,7 +6418,7 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args)
|
|||||||
statusType = b3GetStatusType(statusHandle);
|
statusType = b3GetStatusType(statusHandle);
|
||||||
if (statusType == CMD_CAMERA_IMAGE_COMPLETED)
|
if (statusType == CMD_CAMERA_IMAGE_COMPLETED)
|
||||||
{
|
{
|
||||||
PyObject* item2;
|
|
||||||
PyObject* pyResultList; // store 4 elements in this result: width,
|
PyObject* pyResultList; // store 4 elements in this result: width,
|
||||||
// height, rgbData, depth
|
// height, rgbData, depth
|
||||||
|
|
||||||
@@ -6421,16 +6427,15 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args)
|
|||||||
PyObject* pyDep;
|
PyObject* pyDep;
|
||||||
PyObject* pySeg;
|
PyObject* pySeg;
|
||||||
|
|
||||||
int i, j, p;
|
|
||||||
|
int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values
|
||||||
|
|
||||||
b3GetCameraImageData(sm, &imageData);
|
b3GetCameraImageData(sm, &imageData);
|
||||||
// TODO(hellojas): error handling if image size is 0
|
// TODO(hellojas): error handling if image size is 0
|
||||||
pyResultList = PyTuple_New(5);
|
pyResultList = PyTuple_New(5);
|
||||||
PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth));
|
PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth));
|
||||||
PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight));
|
PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight));
|
||||||
|
{
|
||||||
int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values
|
|
||||||
|
|
||||||
npy_intp rgb_dims[3] = {imageData.m_pixelHeight, imageData.m_pixelWidth,
|
npy_intp rgb_dims[3] = {imageData.m_pixelHeight, imageData.m_pixelWidth,
|
||||||
bytesPerPixel};
|
bytesPerPixel};
|
||||||
npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth};
|
npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth};
|
||||||
@@ -6450,7 +6455,9 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args)
|
|||||||
PyTuple_SetItem(pyResultList, 2, pyRGB);
|
PyTuple_SetItem(pyResultList, 2, pyRGB);
|
||||||
PyTuple_SetItem(pyResultList, 3, pyDep);
|
PyTuple_SetItem(pyResultList, 3, pyDep);
|
||||||
PyTuple_SetItem(pyResultList, 4, pySeg);
|
PyTuple_SetItem(pyResultList, 4, pySeg);
|
||||||
|
}
|
||||||
#else //PYBULLET_USE_NUMPY
|
#else //PYBULLET_USE_NUMPY
|
||||||
|
PyObject* item2;
|
||||||
PyObject* pylistRGB;
|
PyObject* pylistRGB;
|
||||||
PyObject* pylistDep;
|
PyObject* pylistDep;
|
||||||
PyObject* pylistSeg;
|
PyObject* pylistSeg;
|
||||||
@@ -8209,6 +8216,9 @@ initpybullet(void)
|
|||||||
PyModule_AddIntConstant(m, "COV_ENABLE_KEYBOARD_SHORTCUTS", COV_ENABLE_KEYBOARD_SHORTCUTS);
|
PyModule_AddIntConstant(m, "COV_ENABLE_KEYBOARD_SHORTCUTS", COV_ENABLE_KEYBOARD_SHORTCUTS);
|
||||||
PyModule_AddIntConstant(m, "COV_ENABLE_MOUSE_PICKING", COV_ENABLE_MOUSE_PICKING);
|
PyModule_AddIntConstant(m, "COV_ENABLE_MOUSE_PICKING", COV_ENABLE_MOUSE_PICKING);
|
||||||
|
|
||||||
|
PyModule_AddIntConstant(m, "COV_ENABLE_RGB_BUFFER_PREVIEW", COV_ENABLE_RGB_BUFFER_PREVIEW);
|
||||||
|
PyModule_AddIntConstant(m, "COV_ENABLE_DEPTH_BUFFER_PREVIEW", COV_ENABLE_DEPTH_BUFFER_PREVIEW);
|
||||||
|
PyModule_AddIntConstant(m, "COV_ENABLE_SEGMENTATION_MARK_PREVIEW", COV_ENABLE_SEGMENTATION_MARK_PREVIEW);
|
||||||
|
|
||||||
PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER);
|
PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER);
|
||||||
PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL);
|
PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL);
|
||||||
|
|||||||
3
setup.py
3
setup.py
@@ -274,6 +274,7 @@ sources = ["examples/pybullet/pybullet.c"]\
|
|||||||
+["Extras/Serialize/BulletFileLoader/bDNA.cpp"]\
|
+["Extras/Serialize/BulletFileLoader/bDNA.cpp"]\
|
||||||
+["Extras/Serialize/BulletFileLoader/bFile.cpp"]\
|
+["Extras/Serialize/BulletFileLoader/bFile.cpp"]\
|
||||||
+["Extras/Serialize/BulletFileLoader/btBulletFile.cpp"]\
|
+["Extras/Serialize/BulletFileLoader/btBulletFile.cpp"]\
|
||||||
|
+["Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp"]\
|
||||||
+["Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp"]\
|
+["Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp"]\
|
||||||
+["Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp"]\
|
+["Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp"]\
|
||||||
+["Extras/InverseDynamics/CloneTreeCreator.cpp"]\
|
+["Extras/InverseDynamics/CloneTreeCreator.cpp"]\
|
||||||
@@ -441,7 +442,7 @@ print("-----")
|
|||||||
|
|
||||||
setup(
|
setup(
|
||||||
name = 'pybullet',
|
name = 'pybullet',
|
||||||
version='1.6.6',
|
version='1.7.3',
|
||||||
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
|
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
|
||||||
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
|
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
|
||||||
url='https://github.com/bulletphysics/bullet3',
|
url='https://github.com/bulletphysics/bullet3',
|
||||||
|
|||||||
@@ -1646,7 +1646,7 @@ void btCollisionWorld::serializeCollisionObjects(btSerializer* serializer)
|
|||||||
for (i=0;i<m_collisionObjects.size();i++)
|
for (i=0;i<m_collisionObjects.size();i++)
|
||||||
{
|
{
|
||||||
btCollisionObject* colObj = m_collisionObjects[i];
|
btCollisionObject* colObj = m_collisionObjects[i];
|
||||||
if ((colObj->getInternalType() == btCollisionObject::CO_COLLISION_OBJECT) || (colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK))
|
if (colObj->getInternalType() == btCollisionObject::CO_COLLISION_OBJECT)
|
||||||
{
|
{
|
||||||
colObj->serializeSingleObject(serializer);
|
colObj->serializeSingleObject(serializer);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -70,14 +70,32 @@ btScalar btMultiBodyConstraintSolver::solveSingleIteration(int iteration, btColl
|
|||||||
|
|
||||||
//solve featherstone frictional contact
|
//solve featherstone frictional contact
|
||||||
|
|
||||||
for (int j1=0;j1<this->m_multiBodyFrictionContactConstraints.size();j1++)
|
for (int j1=0;j1<this->m_multiBodyLateralFrictionContactConstraints.size();j1++)
|
||||||
{
|
{
|
||||||
if (iteration < infoGlobal.m_numIterations)
|
if (iteration < infoGlobal.m_numIterations)
|
||||||
{
|
{
|
||||||
int index = j1;//iteration&1? j1 : m_multiBodyFrictionContactConstraints.size()-1-j1;
|
int index = j1;//iteration&1? j1 : m_multiBodyFrictionContactConstraints.size()-1-j1;
|
||||||
|
btMultiBodySolverConstraint& frictionConstraint = m_multiBodyLateralFrictionContactConstraints[index];
|
||||||
|
|
||||||
btMultiBodySolverConstraint& frictionConstraint = m_multiBodyFrictionContactConstraints[index];
|
|
||||||
btScalar totalImpulse = m_multiBodyNormalContactConstraints[frictionConstraint.m_frictionIndex].m_appliedImpulse;
|
btScalar totalImpulse = m_multiBodyNormalContactConstraints[frictionConstraint.m_frictionIndex].m_appliedImpulse;
|
||||||
|
if (infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS)
|
||||||
|
{
|
||||||
|
j1++;
|
||||||
|
int index2 = j1;//iteration&1? j1 : m_multiBodyFrictionContactConstraints.size()-1-j1;
|
||||||
|
btMultiBodySolverConstraint& frictionConstraintB = m_multiBodyLateralFrictionContactConstraints[index2];
|
||||||
|
btAssert(frictionConstraint.m_frictionIndex == frictionConstraintB.m_frictionIndex);
|
||||||
|
|
||||||
|
if (frictionConstraint.m_frictionIndex == frictionConstraintB.m_frictionIndex)
|
||||||
|
{
|
||||||
|
frictionConstraint.m_lowerLimit = -(frictionConstraint.m_friction*totalImpulse);
|
||||||
|
frictionConstraint.m_upperLimit = frictionConstraint.m_friction*totalImpulse;
|
||||||
|
frictionConstraintB.m_lowerLimit = -(frictionConstraintB.m_friction*totalImpulse);
|
||||||
|
frictionConstraintB.m_upperLimit = frictionConstraintB.m_friction*totalImpulse;
|
||||||
|
resolveConeFrictionConstraintRows(frictionConstraint,frictionConstraintB);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
//adjust friction limits here
|
//adjust friction limits here
|
||||||
if (totalImpulse > btScalar(0))
|
if (totalImpulse > btScalar(0))
|
||||||
{
|
{
|
||||||
@@ -93,6 +111,7 @@ btScalar btMultiBodyConstraintSolver::solveSingleIteration(int iteration, btColl
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
return leastSquaredResidual;
|
return leastSquaredResidual;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -100,7 +119,9 @@ btScalar btMultiBodyConstraintSolver::solveGroupCacheFriendlySetup(btCollisionOb
|
|||||||
{
|
{
|
||||||
m_multiBodyNonContactConstraints.resize(0);
|
m_multiBodyNonContactConstraints.resize(0);
|
||||||
m_multiBodyNormalContactConstraints.resize(0);
|
m_multiBodyNormalContactConstraints.resize(0);
|
||||||
m_multiBodyFrictionContactConstraints.resize(0);
|
m_multiBodyLateralFrictionContactConstraints.resize(0);
|
||||||
|
m_multiBodyTorsionalFrictionContactConstraints.resize(0);
|
||||||
|
|
||||||
m_data.m_jacobians.resize(0);
|
m_data.m_jacobians.resize(0);
|
||||||
m_data.m_deltaVelocitiesUnitImpulse.resize(0);
|
m_data.m_deltaVelocitiesUnitImpulse.resize(0);
|
||||||
m_data.m_deltaVelocities.resize(0);
|
m_data.m_deltaVelocities.resize(0);
|
||||||
@@ -141,7 +162,8 @@ btScalar btMultiBodyConstraintSolver::resolveSingleConstraintRowGeneric(const bt
|
|||||||
ndofA = c.m_multiBodyA->getNumDofs() + 6;
|
ndofA = c.m_multiBodyA->getNumDofs() + 6;
|
||||||
for (int i = 0; i < ndofA; ++i)
|
for (int i = 0; i < ndofA; ++i)
|
||||||
deltaVelADotn += m_data.m_jacobians[c.m_jacAindex + i] * m_data.m_deltaVelocities[c.m_deltaVelAindex + i];
|
deltaVelADotn += m_data.m_jacobians[c.m_jacAindex + i] * m_data.m_deltaVelocities[c.m_deltaVelAindex + i];
|
||||||
} else if(c.m_solverBodyIdA >= 0)
|
}
|
||||||
|
else if (c.m_solverBodyIdA >= 0)
|
||||||
{
|
{
|
||||||
bodyA = &m_tmpSolverBodyPool[c.m_solverBodyIdA];
|
bodyA = &m_tmpSolverBodyPool[c.m_solverBodyIdA];
|
||||||
deltaVelADotn += c.m_contactNormal1.dot(bodyA->internalGetDeltaLinearVelocity()) + c.m_relpos1CrossNormal.dot(bodyA->internalGetDeltaAngularVelocity());
|
deltaVelADotn += c.m_contactNormal1.dot(bodyA->internalGetDeltaLinearVelocity()) + c.m_relpos1CrossNormal.dot(bodyA->internalGetDeltaAngularVelocity());
|
||||||
@@ -152,7 +174,8 @@ btScalar btMultiBodyConstraintSolver::resolveSingleConstraintRowGeneric(const bt
|
|||||||
ndofB = c.m_multiBodyB->getNumDofs() + 6;
|
ndofB = c.m_multiBodyB->getNumDofs() + 6;
|
||||||
for (int i = 0; i < ndofB; ++i)
|
for (int i = 0; i < ndofB; ++i)
|
||||||
deltaVelBDotn += m_data.m_jacobians[c.m_jacBindex + i] * m_data.m_deltaVelocities[c.m_deltaVelBindex + i];
|
deltaVelBDotn += m_data.m_jacobians[c.m_jacBindex + i] * m_data.m_deltaVelocities[c.m_deltaVelBindex + i];
|
||||||
} else if(c.m_solverBodyIdB >= 0)
|
}
|
||||||
|
else if (c.m_solverBodyIdB >= 0)
|
||||||
{
|
{
|
||||||
bodyB = &m_tmpSolverBodyPool[c.m_solverBodyIdB];
|
bodyB = &m_tmpSolverBodyPool[c.m_solverBodyIdB];
|
||||||
deltaVelBDotn += c.m_contactNormal2.dot(bodyB->internalGetDeltaLinearVelocity()) + c.m_relpos2CrossNormal.dot(bodyB->internalGetDeltaAngularVelocity());
|
deltaVelBDotn += c.m_contactNormal2.dot(bodyB->internalGetDeltaLinearVelocity()) + c.m_relpos2CrossNormal.dot(bodyB->internalGetDeltaAngularVelocity());
|
||||||
@@ -186,7 +209,8 @@ btScalar btMultiBodyConstraintSolver::resolveSingleConstraintRowGeneric(const bt
|
|||||||
//it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity
|
//it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity
|
||||||
c.m_multiBodyA->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacAindex], deltaImpulse);
|
c.m_multiBodyA->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacAindex], deltaImpulse);
|
||||||
#endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
|
#endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
|
||||||
} else if(c.m_solverBodyIdA >= 0)
|
}
|
||||||
|
else if (c.m_solverBodyIdA >= 0)
|
||||||
{
|
{
|
||||||
bodyA->internalApplyImpulse(c.m_contactNormal1*bodyA->internalGetInvMass(), c.m_angularComponentA, deltaImpulse);
|
bodyA->internalApplyImpulse(c.m_contactNormal1*bodyA->internalGetInvMass(), c.m_angularComponentA, deltaImpulse);
|
||||||
|
|
||||||
@@ -199,7 +223,8 @@ btScalar btMultiBodyConstraintSolver::resolveSingleConstraintRowGeneric(const bt
|
|||||||
//it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity
|
//it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity
|
||||||
c.m_multiBodyB->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacBindex], deltaImpulse);
|
c.m_multiBodyB->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacBindex], deltaImpulse);
|
||||||
#endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
|
#endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
|
||||||
} else if(c.m_solverBodyIdB >= 0)
|
}
|
||||||
|
else if (c.m_solverBodyIdB >= 0)
|
||||||
{
|
{
|
||||||
bodyB->internalApplyImpulse(c.m_contactNormal2*bodyB->internalGetInvMass(), c.m_angularComponentB, deltaImpulse);
|
bodyB->internalApplyImpulse(c.m_contactNormal2*bodyB->internalGetInvMass(), c.m_angularComponentB, deltaImpulse);
|
||||||
}
|
}
|
||||||
@@ -207,6 +232,185 @@ btScalar btMultiBodyConstraintSolver::resolveSingleConstraintRowGeneric(const bt
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
btScalar btMultiBodyConstraintSolver::resolveConeFrictionConstraintRows(const btMultiBodySolverConstraint& cA1,const btMultiBodySolverConstraint& cB)
|
||||||
|
{
|
||||||
|
int ndofA=0;
|
||||||
|
int ndofB=0;
|
||||||
|
btSolverBody* bodyA = 0;
|
||||||
|
btSolverBody* bodyB = 0;
|
||||||
|
btScalar deltaImpulseB = 0.f;
|
||||||
|
btScalar sumB = 0.f;
|
||||||
|
{
|
||||||
|
deltaImpulseB = cB.m_rhs-btScalar(cB.m_appliedImpulse)*cB.m_cfm;
|
||||||
|
btScalar deltaVelADotn=0;
|
||||||
|
btScalar deltaVelBDotn=0;
|
||||||
|
if (cB.m_multiBodyA)
|
||||||
|
{
|
||||||
|
ndofA = cB.m_multiBodyA->getNumDofs() + 6;
|
||||||
|
for (int i = 0; i < ndofA; ++i)
|
||||||
|
deltaVelADotn += m_data.m_jacobians[cB.m_jacAindex+i] * m_data.m_deltaVelocities[cB.m_deltaVelAindex+i];
|
||||||
|
} else if(cB.m_solverBodyIdA >= 0)
|
||||||
|
{
|
||||||
|
bodyA = &m_tmpSolverBodyPool[cB.m_solverBodyIdA];
|
||||||
|
deltaVelADotn += cB.m_contactNormal1.dot(bodyA->internalGetDeltaLinearVelocity()) + cB.m_relpos1CrossNormal.dot(bodyA->internalGetDeltaAngularVelocity());
|
||||||
|
}
|
||||||
|
|
||||||
|
if (cB.m_multiBodyB)
|
||||||
|
{
|
||||||
|
ndofB = cB.m_multiBodyB->getNumDofs() + 6;
|
||||||
|
for (int i = 0; i < ndofB; ++i)
|
||||||
|
deltaVelBDotn += m_data.m_jacobians[cB.m_jacBindex+i] * m_data.m_deltaVelocities[cB.m_deltaVelBindex+i];
|
||||||
|
} else if(cB.m_solverBodyIdB >= 0)
|
||||||
|
{
|
||||||
|
bodyB = &m_tmpSolverBodyPool[cB.m_solverBodyIdB];
|
||||||
|
deltaVelBDotn += cB.m_contactNormal2.dot(bodyB->internalGetDeltaLinearVelocity()) + cB.m_relpos2CrossNormal.dot(bodyB->internalGetDeltaAngularVelocity());
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
deltaImpulseB -= deltaVelADotn*cB.m_jacDiagABInv;//m_jacDiagABInv = 1./denom
|
||||||
|
deltaImpulseB -= deltaVelBDotn*cB.m_jacDiagABInv;
|
||||||
|
sumB = btScalar(cB.m_appliedImpulse) + deltaImpulseB;
|
||||||
|
}
|
||||||
|
|
||||||
|
btScalar deltaImpulseA = 0.f;
|
||||||
|
btScalar sumA = 0.f;
|
||||||
|
const btMultiBodySolverConstraint& cA = cA1;
|
||||||
|
{
|
||||||
|
{
|
||||||
|
deltaImpulseA = cA.m_rhs-btScalar(cA.m_appliedImpulse)*cA.m_cfm;
|
||||||
|
btScalar deltaVelADotn=0;
|
||||||
|
btScalar deltaVelBDotn=0;
|
||||||
|
if (cA.m_multiBodyA)
|
||||||
|
{
|
||||||
|
ndofA = cA.m_multiBodyA->getNumDofs() + 6;
|
||||||
|
for (int i = 0; i < ndofA; ++i)
|
||||||
|
deltaVelADotn += m_data.m_jacobians[cA.m_jacAindex+i] * m_data.m_deltaVelocities[cA.m_deltaVelAindex+i];
|
||||||
|
} else if(cA.m_solverBodyIdA >= 0)
|
||||||
|
{
|
||||||
|
bodyA = &m_tmpSolverBodyPool[cA.m_solverBodyIdA];
|
||||||
|
deltaVelADotn += cA.m_contactNormal1.dot(bodyA->internalGetDeltaLinearVelocity()) + cA.m_relpos1CrossNormal.dot(bodyA->internalGetDeltaAngularVelocity());
|
||||||
|
}
|
||||||
|
|
||||||
|
if (cA.m_multiBodyB)
|
||||||
|
{
|
||||||
|
ndofB = cA.m_multiBodyB->getNumDofs() + 6;
|
||||||
|
for (int i = 0; i < ndofB; ++i)
|
||||||
|
deltaVelBDotn += m_data.m_jacobians[cA.m_jacBindex+i] * m_data.m_deltaVelocities[cA.m_deltaVelBindex+i];
|
||||||
|
} else if(cA.m_solverBodyIdB >= 0)
|
||||||
|
{
|
||||||
|
bodyB = &m_tmpSolverBodyPool[cA.m_solverBodyIdB];
|
||||||
|
deltaVelBDotn += cA.m_contactNormal2.dot(bodyB->internalGetDeltaLinearVelocity()) + cA.m_relpos2CrossNormal.dot(bodyB->internalGetDeltaAngularVelocity());
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
deltaImpulseA -= deltaVelADotn*cA.m_jacDiagABInv;//m_jacDiagABInv = 1./denom
|
||||||
|
deltaImpulseA -= deltaVelBDotn*cA.m_jacDiagABInv;
|
||||||
|
sumA = btScalar(cA.m_appliedImpulse) + deltaImpulseA;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sumA*sumA+sumB*sumB>=cA.m_lowerLimit*cB.m_lowerLimit)
|
||||||
|
{
|
||||||
|
btScalar angle = btAtan2(sumA,sumB);
|
||||||
|
btScalar sumAclipped = btFabs(cA.m_lowerLimit*btSin(angle));
|
||||||
|
btScalar sumBclipped = btFabs(cB.m_lowerLimit*btCos(angle));
|
||||||
|
|
||||||
|
|
||||||
|
if (sumA < -sumAclipped)
|
||||||
|
{
|
||||||
|
deltaImpulseA = -sumAclipped - cA.m_appliedImpulse;
|
||||||
|
cA.m_appliedImpulse = -sumAclipped;
|
||||||
|
}
|
||||||
|
else if (sumA > sumAclipped)
|
||||||
|
{
|
||||||
|
deltaImpulseA = sumAclipped - cA.m_appliedImpulse;
|
||||||
|
cA.m_appliedImpulse = sumAclipped;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
cA.m_appliedImpulse = sumA;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sumB < -sumBclipped)
|
||||||
|
{
|
||||||
|
deltaImpulseB = -sumBclipped - cB.m_appliedImpulse;
|
||||||
|
cB.m_appliedImpulse = -sumBclipped;
|
||||||
|
}
|
||||||
|
else if (sumB > sumBclipped)
|
||||||
|
{
|
||||||
|
deltaImpulseB = sumBclipped - cB.m_appliedImpulse;
|
||||||
|
cB.m_appliedImpulse = sumBclipped;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
cB.m_appliedImpulse = sumB;
|
||||||
|
}
|
||||||
|
//deltaImpulseA = sumAclipped-cA.m_appliedImpulse;
|
||||||
|
//cA.m_appliedImpulse = sumAclipped;
|
||||||
|
//deltaImpulseB = sumBclipped-cB.m_appliedImpulse;
|
||||||
|
//cB.m_appliedImpulse = sumBclipped;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
cA.m_appliedImpulse = sumA;
|
||||||
|
cB.m_appliedImpulse = sumB;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (cA.m_multiBodyA)
|
||||||
|
{
|
||||||
|
applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[cA.m_jacAindex],deltaImpulseA,cA.m_deltaVelAindex,ndofA);
|
||||||
|
#ifdef DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
|
||||||
|
//note: update of the actual velocities (below) in the multibody does not have to happen now since m_deltaVelocities can be applied after all iterations
|
||||||
|
//it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity
|
||||||
|
cA.m_multiBodyA->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[cA.m_jacAindex],deltaImpulseA);
|
||||||
|
#endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
|
||||||
|
} else if(cA.m_solverBodyIdA >= 0)
|
||||||
|
{
|
||||||
|
bodyA->internalApplyImpulse(cA.m_contactNormal1*bodyA->internalGetInvMass(),cA.m_angularComponentA,deltaImpulseA);
|
||||||
|
|
||||||
|
}
|
||||||
|
if (cA.m_multiBodyB)
|
||||||
|
{
|
||||||
|
applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[cA.m_jacBindex],deltaImpulseA,cA.m_deltaVelBindex,ndofB);
|
||||||
|
#ifdef DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
|
||||||
|
//note: update of the actual velocities (below) in the multibody does not have to happen now since m_deltaVelocities can be applied after all iterations
|
||||||
|
//it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity
|
||||||
|
cA.m_multiBodyB->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[cA.m_jacBindex],deltaImpulseA);
|
||||||
|
#endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
|
||||||
|
} else if(cA.m_solverBodyIdB >= 0)
|
||||||
|
{
|
||||||
|
bodyB->internalApplyImpulse(cA.m_contactNormal2*bodyB->internalGetInvMass(),cA.m_angularComponentB,deltaImpulseA);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (cB.m_multiBodyA)
|
||||||
|
{
|
||||||
|
applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[cB.m_jacAindex],deltaImpulseB,cB.m_deltaVelAindex,ndofA);
|
||||||
|
#ifdef DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
|
||||||
|
//note: update of the actual velocities (below) in the multibody does not have to happen now since m_deltaVelocities can be applied after all iterations
|
||||||
|
//it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity
|
||||||
|
cB.m_multiBodyA->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[cB.m_jacAindex],deltaImpulseB);
|
||||||
|
#endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
|
||||||
|
} else if(cB.m_solverBodyIdA >= 0)
|
||||||
|
{
|
||||||
|
bodyA->internalApplyImpulse(cB.m_contactNormal1*bodyA->internalGetInvMass(),cB.m_angularComponentA,deltaImpulseB);
|
||||||
|
}
|
||||||
|
if (cB.m_multiBodyB)
|
||||||
|
{
|
||||||
|
applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[cB.m_jacBindex],deltaImpulseB,cB.m_deltaVelBindex,ndofB);
|
||||||
|
#ifdef DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
|
||||||
|
//note: update of the actual velocities (below) in the multibody does not have to happen now since m_deltaVelocities can be applied after all iterations
|
||||||
|
//it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity
|
||||||
|
cB.m_multiBodyB->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[cB.m_jacBindex],deltaImpulseB);
|
||||||
|
#endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
|
||||||
|
} else if(cB.m_solverBodyIdB >= 0)
|
||||||
|
{
|
||||||
|
bodyB->internalApplyImpulse(cB.m_contactNormal2*bodyB->internalGetInvMass(),cB.m_angularComponentB,deltaImpulseB);
|
||||||
|
}
|
||||||
|
|
||||||
|
return deltaImpulseA+deltaImpulseB;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySolverConstraint& solverConstraint,
|
void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySolverConstraint& solverConstraint,
|
||||||
@@ -871,7 +1075,7 @@ void btMultiBodyConstraintSolver::setupMultiBodyTorsionalFrictionConstraint(btMu
|
|||||||
btMultiBodySolverConstraint& btMultiBodyConstraintSolver::addMultiBodyFrictionConstraint(const btVector3& normalAxis,btPersistentManifold* manifold,int frictionIndex,btManifoldPoint& cp,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip)
|
btMultiBodySolverConstraint& btMultiBodyConstraintSolver::addMultiBodyFrictionConstraint(const btVector3& normalAxis,btPersistentManifold* manifold,int frictionIndex,btManifoldPoint& cp,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip)
|
||||||
{
|
{
|
||||||
BT_PROFILE("addMultiBodyFrictionConstraint");
|
BT_PROFILE("addMultiBodyFrictionConstraint");
|
||||||
btMultiBodySolverConstraint& solverConstraint = m_multiBodyFrictionContactConstraints.expandNonInitializing();
|
btMultiBodySolverConstraint& solverConstraint = m_multiBodyLateralFrictionContactConstraints.expandNonInitializing();
|
||||||
solverConstraint.m_orgConstraint = 0;
|
solverConstraint.m_orgConstraint = 0;
|
||||||
solverConstraint.m_orgDofIndex = -1;
|
solverConstraint.m_orgDofIndex = -1;
|
||||||
|
|
||||||
@@ -908,7 +1112,7 @@ btMultiBodySolverConstraint& btMultiBodyConstraintSolver::addMultiBodyTorsionalF
|
|||||||
btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip)
|
btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip)
|
||||||
{
|
{
|
||||||
BT_PROFILE("addMultiBodyRollingFrictionConstraint");
|
BT_PROFILE("addMultiBodyRollingFrictionConstraint");
|
||||||
btMultiBodySolverConstraint& solverConstraint = m_multiBodyFrictionContactConstraints.expandNonInitializing();
|
btMultiBodySolverConstraint& solverConstraint = m_multiBodyTorsionalFrictionContactConstraints.expandNonInitializing();
|
||||||
solverConstraint.m_orgConstraint = 0;
|
solverConstraint.m_orgConstraint = 0;
|
||||||
solverConstraint.m_orgDofIndex = -1;
|
solverConstraint.m_orgDofIndex = -1;
|
||||||
|
|
||||||
@@ -1275,11 +1479,11 @@ btScalar btMultiBodyConstraintSolver::solveGroupCacheFriendlyFinish(btCollisionO
|
|||||||
btMultiBodySolverConstraint& solverConstraint = m_multiBodyNormalContactConstraints[i];
|
btMultiBodySolverConstraint& solverConstraint = m_multiBodyNormalContactConstraints[i];
|
||||||
writeBackSolverBodyToMultiBody(solverConstraint,infoGlobal.m_timeStep);
|
writeBackSolverBodyToMultiBody(solverConstraint,infoGlobal.m_timeStep);
|
||||||
|
|
||||||
writeBackSolverBodyToMultiBody(m_multiBodyFrictionContactConstraints[solverConstraint.m_frictionIndex],infoGlobal.m_timeStep);
|
writeBackSolverBodyToMultiBody(m_multiBodyLateralFrictionContactConstraints[solverConstraint.m_frictionIndex],infoGlobal.m_timeStep);
|
||||||
|
|
||||||
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
|
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
|
||||||
{
|
{
|
||||||
writeBackSolverBodyToMultiBody(m_multiBodyFrictionContactConstraints[solverConstraint.m_frictionIndex+1],infoGlobal.m_timeStep);
|
writeBackSolverBodyToMultiBody(m_multiBodyLateralFrictionContactConstraints[solverConstraint.m_frictionIndex+1],infoGlobal.m_timeStep);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -1300,12 +1504,12 @@ btScalar btMultiBodyConstraintSolver::solveGroupCacheFriendlyFinish(btCollisionO
|
|||||||
btManifoldPoint* pt = (btManifoldPoint*) solverConstraint.m_originalContactPoint;
|
btManifoldPoint* pt = (btManifoldPoint*) solverConstraint.m_originalContactPoint;
|
||||||
btAssert(pt);
|
btAssert(pt);
|
||||||
pt->m_appliedImpulse = solverConstraint.m_appliedImpulse;
|
pt->m_appliedImpulse = solverConstraint.m_appliedImpulse;
|
||||||
pt->m_appliedImpulseLateral1 = m_multiBodyFrictionContactConstraints[solverConstraint.m_frictionIndex].m_appliedImpulse;
|
pt->m_appliedImpulseLateral1 = m_multiBodyLateralFrictionContactConstraints[solverConstraint.m_frictionIndex].m_appliedImpulse;
|
||||||
|
|
||||||
//printf("pt->m_appliedImpulseLateral1 = %f\n", pt->m_appliedImpulseLateral1);
|
//printf("pt->m_appliedImpulseLateral1 = %f\n", pt->m_appliedImpulseLateral1);
|
||||||
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
|
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
|
||||||
{
|
{
|
||||||
pt->m_appliedImpulseLateral2 = m_multiBodyFrictionContactConstraints[solverConstraint.m_frictionIndex+1].m_appliedImpulse;
|
pt->m_appliedImpulseLateral2 = m_multiBodyLateralFrictionContactConstraints[solverConstraint.m_frictionIndex+1].m_appliedImpulse;
|
||||||
}
|
}
|
||||||
//do a callback here?
|
//do a callback here?
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -35,7 +35,8 @@ protected:
|
|||||||
btMultiBodyConstraintArray m_multiBodyNonContactConstraints;
|
btMultiBodyConstraintArray m_multiBodyNonContactConstraints;
|
||||||
|
|
||||||
btMultiBodyConstraintArray m_multiBodyNormalContactConstraints;
|
btMultiBodyConstraintArray m_multiBodyNormalContactConstraints;
|
||||||
btMultiBodyConstraintArray m_multiBodyFrictionContactConstraints;
|
btMultiBodyConstraintArray m_multiBodyLateralFrictionContactConstraints;
|
||||||
|
btMultiBodyConstraintArray m_multiBodyTorsionalFrictionContactConstraints;
|
||||||
|
|
||||||
btMultiBodyJacobianData m_data;
|
btMultiBodyJacobianData m_data;
|
||||||
|
|
||||||
@@ -45,6 +46,9 @@ protected:
|
|||||||
|
|
||||||
btScalar resolveSingleConstraintRowGeneric(const btMultiBodySolverConstraint& c);
|
btScalar resolveSingleConstraintRowGeneric(const btMultiBodySolverConstraint& c);
|
||||||
|
|
||||||
|
//solve 2 friction directions and clamp against the implicit friction cone
|
||||||
|
btScalar resolveConeFrictionConstraintRows(const btMultiBodySolverConstraint& cA, const btMultiBodySolverConstraint& cB);
|
||||||
|
|
||||||
|
|
||||||
void convertContacts(btPersistentManifold** manifoldPtr,int numManifolds, const btContactSolverInfo& infoGlobal);
|
void convertContacts(btPersistentManifold** manifoldPtr,int numManifolds, const btContactSolverInfo& infoGlobal);
|
||||||
|
|
||||||
|
|||||||
@@ -990,4 +990,17 @@ void btMultiBodyDynamicsWorld::serializeMultiBodies(btSerializer* serializer)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
//serialize all multibody links (collision objects)
|
||||||
|
for (i=0;i<m_collisionObjects.size();i++)
|
||||||
|
{
|
||||||
|
btCollisionObject* colObj = m_collisionObjects[i];
|
||||||
|
if (colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK)
|
||||||
|
{
|
||||||
|
int len = colObj->calculateSerializeBufferSize();
|
||||||
|
btChunk* chunk = serializer->allocate(len,1);
|
||||||
|
const char* structType = colObj->serialize(chunk->m_oldPtr, serializer);
|
||||||
|
serializer->finalizeChunk(chunk,structType,BT_MB_LINKCOLLIDER_CODE,colObj);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
@@ -19,6 +19,16 @@ subject to the following restrictions:
|
|||||||
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
|
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
|
||||||
|
|
||||||
#include "btMultiBody.h"
|
#include "btMultiBody.h"
|
||||||
|
#include "LinearMath/btSerializer.h"
|
||||||
|
|
||||||
|
#ifdef BT_USE_DOUBLE_PRECISION
|
||||||
|
#define btMultiBodyLinkColliderData btMultiBodyLinkColliderDoubleData
|
||||||
|
#define btMultiBodyLinkColliderDataName "btMultiBodyLinkColliderDoubleData"
|
||||||
|
#else
|
||||||
|
#define btMultiBodyLinkColliderData btMultiBodyLinkColliderFloatData
|
||||||
|
#define btMultiBodyLinkColliderDataName "btMultiBodyLinkColliderFloatData"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
class btMultiBodyLinkCollider : public btCollisionObject
|
class btMultiBodyLinkCollider : public btCollisionObject
|
||||||
{
|
{
|
||||||
@@ -119,7 +129,49 @@ public:
|
|||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
virtual int calculateSerializeBufferSize() const;
|
||||||
|
|
||||||
|
///fills the dataBuffer and returns the struct name (and 0 on failure)
|
||||||
|
virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
struct btMultiBodyLinkColliderFloatData
|
||||||
|
{
|
||||||
|
btCollisionObjectFloatData m_colObjData;
|
||||||
|
void *m_multiBody;
|
||||||
|
int m_link;
|
||||||
|
char m_padding[4];
|
||||||
|
};
|
||||||
|
|
||||||
|
struct btMultiBodyLinkColliderDoubleData
|
||||||
|
{
|
||||||
|
btCollisionObjectDoubleData m_colObjData;
|
||||||
|
void *m_multiBody;
|
||||||
|
int m_link;
|
||||||
|
char m_padding[4];
|
||||||
|
};
|
||||||
|
|
||||||
|
SIMD_FORCE_INLINE int btMultiBodyLinkCollider::calculateSerializeBufferSize() const
|
||||||
|
{
|
||||||
|
return sizeof(btMultiBodyLinkColliderData);
|
||||||
|
}
|
||||||
|
|
||||||
|
SIMD_FORCE_INLINE const char* btMultiBodyLinkCollider::serialize(void* dataBuffer, class btSerializer* serializer) const
|
||||||
|
{
|
||||||
|
btMultiBodyLinkColliderData* dataOut = (btMultiBodyLinkColliderData*)dataBuffer;
|
||||||
|
btCollisionObject::serialize(&dataOut->m_colObjData,serializer);
|
||||||
|
|
||||||
|
dataOut->m_link = this->m_link;
|
||||||
|
dataOut->m_multiBody = serializer->getUniquePointer(m_multiBody);
|
||||||
|
|
||||||
|
// Fill padding with zeros to appease msan.
|
||||||
|
memset(dataOut->m_padding, 0, sizeof(dataOut->m_padding));
|
||||||
|
|
||||||
|
return btMultiBodyLinkColliderDataName;
|
||||||
|
}
|
||||||
|
|
||||||
#endif //BT_FEATHERSTONE_LINK_COLLIDER_H
|
#endif //BT_FEATHERSTONE_LINK_COLLIDER_H
|
||||||
|
|
||||||
|
|||||||
@@ -25,7 +25,7 @@ subject to the following restrictions:
|
|||||||
#include <float.h>
|
#include <float.h>
|
||||||
|
|
||||||
/* SVN $Revision$ on $Date$ from http://bullet.googlecode.com*/
|
/* SVN $Revision$ on $Date$ from http://bullet.googlecode.com*/
|
||||||
#define BT_BULLET_VERSION 287
|
#define BT_BULLET_VERSION 288
|
||||||
|
|
||||||
inline int btGetVersion()
|
inline int btGetVersion()
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -1,5 +1,5 @@
|
|||||||
char sBulletDNAstr[]= {
|
char sBulletDNAstr[]= {
|
||||||
char(83),char(68),char(78),char(65),char(78),char(65),char(77),char(69),char(-124),char(1),char(0),char(0),char(109),char(95),char(115),char(105),char(122),char(101),char(0),char(109),
|
char(83),char(68),char(78),char(65),char(78),char(65),char(77),char(69),char(-121),char(1),char(0),char(0),char(109),char(95),char(115),char(105),char(122),char(101),char(0),char(109),
|
||||||
char(95),char(99),char(97),char(112),char(97),char(99),char(105),char(116),char(121),char(0),char(42),char(109),char(95),char(100),char(97),char(116),char(97),char(0),char(109),char(95),
|
char(95),char(99),char(97),char(112),char(97),char(99),char(105),char(116),char(121),char(0),char(42),char(109),char(95),char(100),char(97),char(116),char(97),char(0),char(109),char(95),
|
||||||
char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(115),char(0),char(109),char(95),char(99),char(111),
|
char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(115),char(0),char(109),char(95),char(99),char(111),
|
||||||
char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(115),char(0),char(109),char(95),char(99),char(111),char(110),
|
char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(115),char(0),char(109),char(95),char(99),char(111),char(110),
|
||||||
@@ -316,284 +316,292 @@ char(110),char(103),char(80),char(116),char(114),char(0),char(109),char(95),char
|
|||||||
char(110),char(115),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(73),char(110),char(101),char(114),char(116),char(105),char(97),
|
char(110),char(115),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(73),char(110),char(101),char(114),char(116),char(105),char(97),
|
||||||
char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(77),char(97),char(115),char(115),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(78),
|
char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(77),char(97),char(115),char(115),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(78),
|
||||||
char(97),char(109),char(101),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(0),
|
char(97),char(109),char(101),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(0),
|
||||||
char(84),char(89),char(80),char(69),char(95),char(0),char(0),char(0),char(99),char(104),char(97),char(114),char(0),char(117),char(99),char(104),char(97),char(114),char(0),char(115),
|
char(109),char(95),char(99),char(111),char(108),char(79),char(98),char(106),char(68),char(97),char(116),char(97),char(0),char(42),char(109),char(95),char(109),char(117),char(108),char(116),
|
||||||
char(104),char(111),char(114),char(116),char(0),char(117),char(115),char(104),char(111),char(114),char(116),char(0),char(105),char(110),char(116),char(0),char(108),char(111),char(110),char(103),
|
char(105),char(66),char(111),char(100),char(121),char(0),char(109),char(95),char(108),char(105),char(110),char(107),char(0),char(0),char(0),char(0),char(84),char(89),char(80),char(69),
|
||||||
char(0),char(117),char(108),char(111),char(110),char(103),char(0),char(102),char(108),char(111),char(97),char(116),char(0),char(100),char(111),char(117),char(98),char(108),char(101),char(0),
|
char(97),char(0),char(0),char(0),char(99),char(104),char(97),char(114),char(0),char(117),char(99),char(104),char(97),char(114),char(0),char(115),char(104),char(111),char(114),char(116),
|
||||||
char(118),char(111),char(105),char(100),char(0),char(80),char(111),char(105),char(110),char(116),char(101),char(114),char(65),char(114),char(114),char(97),char(121),char(0),char(98),char(116),
|
char(0),char(117),char(115),char(104),char(111),char(114),char(116),char(0),char(105),char(110),char(116),char(0),char(108),char(111),char(110),char(103),char(0),char(117),char(108),char(111),
|
||||||
char(80),char(104),char(121),char(115),char(105),char(99),char(115),char(83),char(121),char(115),char(116),char(101),char(109),char(0),char(76),char(105),char(115),char(116),char(66),char(97),
|
char(110),char(103),char(0),char(102),char(108),char(111),char(97),char(116),char(0),char(100),char(111),char(117),char(98),char(108),char(101),char(0),char(118),char(111),char(105),char(100),
|
||||||
char(115),char(101),char(0),char(98),char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),
|
char(0),char(80),char(111),char(105),char(110),char(116),char(101),char(114),char(65),char(114),char(114),char(97),char(121),char(0),char(98),char(116),char(80),char(104),char(121),char(115),
|
||||||
char(97),char(0),char(98),char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),
|
char(105),char(99),char(115),char(83),char(121),char(115),char(116),char(101),char(109),char(0),char(76),char(105),char(115),char(116),char(66),char(97),char(115),char(101),char(0),char(98),
|
||||||
char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105),char(111),char(110),char(70),char(108),char(111),char(97),char(116),char(68),
|
char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105),char(111),char(110),char(68),char(111),char(117),char(98),
|
char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
||||||
char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(70),char(108),
|
char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105),char(111),char(110),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(68),
|
char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105),char(111),char(110),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),
|
||||||
char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),
|
char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(70),char(108),char(111),char(97),char(116),char(68),
|
||||||
char(109),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111),
|
char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(68),char(111),char(117),char(98),char(108),
|
||||||
char(114),char(109),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(66),char(118),char(104),char(83),char(117),
|
char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),char(109),char(70),char(108),char(111),
|
||||||
char(98),char(116),char(114),char(101),char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(79),char(112),char(116),char(105),
|
char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),char(109),char(68),char(111),
|
||||||
char(109),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),
|
char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(66),char(118),char(104),char(83),char(117),char(98),char(116),char(114),char(101),
|
||||||
char(97),char(0),char(98),char(116),char(79),char(112),char(116),char(105),char(109),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),
|
char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(79),char(112),char(116),char(105),char(109),char(105),char(122),char(101),
|
||||||
char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122),
|
char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
||||||
char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),
|
char(79),char(112),char(116),char(105),char(109),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(68),char(111),char(117),char(98),
|
||||||
char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),char(100),char(66),char(118),
|
||||||
char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),
|
char(104),char(78),char(111),char(100),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),
|
||||||
char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(68),
|
char(100),char(66),char(118),char(104),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116),char(97),char(116),char(105),char(99),char(80),char(108),char(97),char(110),char(101),char(83),char(104),char(97),
|
char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),
|
||||||
char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(118),char(101),char(120),char(73),char(110),char(116),char(101),char(114),
|
char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(110),char(97),char(108),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(115),char(105),char(116),
|
char(98),char(116),char(83),char(116),char(97),char(116),char(105),char(99),char(80),char(108),char(97),char(110),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),
|
||||||
char(105),char(111),char(110),char(65),char(110),char(100),char(82),char(97),char(100),char(105),char(117),char(115),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),
|
char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(118),char(101),char(120),char(73),char(110),char(116),char(101),char(114),char(110),char(97),char(108),char(83),
|
||||||
char(83),char(112),char(104),char(101),char(114),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(73),char(110),
|
char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(65),
|
||||||
char(116),char(73),char(110),char(100),char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110),
|
char(110),char(100),char(82),char(97),char(100),char(105),char(117),char(115),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(83),char(112),char(104),char(101),
|
||||||
char(116),char(73),char(110),char(100),char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110),
|
char(114),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(73),char(110),char(116),char(73),char(110),char(100),
|
||||||
char(116),char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110),char(116),char(73),char(110),char(100),
|
||||||
char(67),char(104),char(97),char(114),char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97),
|
char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110),char(116),char(73),char(110),char(100),
|
||||||
char(0),char(98),char(116),char(77),char(101),char(115),char(104),char(80),char(97),char(114),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116),
|
char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(104),char(97),char(114),
|
||||||
char(114),char(105),char(100),char(105),char(110),char(103),char(77),char(101),char(115),char(104),char(73),char(110),char(116),char(101),char(114),char(102),char(97),char(99),char(101),char(68),
|
char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104),
|
char(101),char(115),char(104),char(80),char(97),char(114),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116),char(114),char(105),char(100),char(105),
|
||||||
char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110),
|
char(110),char(103),char(77),char(101),char(115),char(104),char(73),char(110),char(116),char(101),char(114),char(102),char(97),char(99),char(101),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(102),char(111),char(77),char(97),char(112),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(99),char(97),char(108),char(101),char(100),char(84),char(114),
|
char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),
|
||||||
char(105),char(97),char(110),char(103),char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),
|
char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110),char(102),char(111),char(77),char(97),
|
||||||
char(98),char(116),char(67),char(111),char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101),char(67),char(104),char(105),char(108),char(100),
|
char(112),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(99),char(97),char(108),char(101),char(100),char(84),char(114),char(105),char(97),char(110),char(103),
|
||||||
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101),
|
char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),
|
||||||
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(121),char(108),char(105),char(110),char(100),char(101),char(114),char(83),char(104),char(97),char(112),char(101),
|
char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101),char(67),char(104),char(105),char(108),char(100),char(68),char(97),char(116),char(97),
|
||||||
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),
|
char(0),char(98),char(116),char(67),char(111),char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),
|
||||||
char(0),char(98),char(116),char(67),char(97),char(112),char(115),char(117),char(108),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),
|
char(0),char(98),char(116),char(67),char(121),char(108),char(105),char(110),char(100),char(101),char(114),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),
|
||||||
char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98),
|
char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),
|
||||||
char(116),char(71),char(73),char(109),char(112),char(97),char(99),char(116),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),
|
char(97),char(112),char(115),char(117),char(108),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),
|
||||||
char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(118),char(101),char(120),char(72),char(117),char(108),char(108),char(83),char(104),char(97),char(112),char(101),char(68),
|
char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(73),char(109),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),
|
char(112),char(97),char(99),char(116),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
||||||
char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),
|
char(67),char(111),char(110),char(118),char(101),char(120),char(72),char(117),char(108),char(108),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),
|
char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(68),char(111),char(117),
|
||||||
char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111),char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(68),char(111),
|
char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),
|
||||||
char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111),
|
char(98),char(106),char(101),char(99),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),
|
||||||
char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
char(116),char(97),char(99),char(116),char(83),char(111),char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(68),char(111),char(117),char(98),char(108),char(101),
|
||||||
char(68),char(121),char(110),char(97),char(109),char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(68),char(111),char(117),char(98),char(108),char(101),char(68),
|
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111),char(108),char(118),char(101),char(114),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(68),char(121),char(110),char(97),char(109),char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(70),
|
char(73),char(110),char(102),char(111),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(68),char(121),char(110),char(97),
|
||||||
char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),
|
char(109),char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),
|
char(98),char(116),char(68),char(121),char(110),char(97),char(109),char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(70),char(108),char(111),char(97),char(116),
|
||||||
char(121),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(115),char(116),char(114),
|
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(70),char(108),char(111),char(97),
|
||||||
char(97),char(105),char(110),char(116),char(73),char(110),char(102),char(111),char(49),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),char(110),
|
char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(68),char(111),char(117),
|
||||||
char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),
|
char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),
|
||||||
char(121),char(112),char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),
|
char(73),char(110),char(102),char(111),char(49),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),
|
||||||
char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(121),char(112),
|
char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),
|
||||||
char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),
|
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),
|
||||||
char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),
|
char(105),char(100),char(66),char(111),char(100),char(121),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),
|
||||||
char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),
|
char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),
|
||||||
char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),
|
char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),
|
||||||
char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),
|
char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),
|
||||||
char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),
|
char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),
|
||||||
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),
|
char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),
|
||||||
char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),
|
|
||||||
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),
|
|
||||||
char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),
|
|
||||||
char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116),
|
|
||||||
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),
|
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),
|
||||||
char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),
|
char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),
|
||||||
char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),
|
char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),
|
||||||
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),
|
char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),
|
||||||
char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),
|
char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),
|
||||||
char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),
|
char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116),char(67),char(111),char(110),char(115),
|
||||||
char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),
|
char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),
|
char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),
|
||||||
char(105),char(110),char(103),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),
|
char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(67),char(111),char(110),char(115),
|
||||||
char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),
|
char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),
|
||||||
char(114),char(105),char(110),char(103),char(50),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),
|
char(54),char(68),char(111),char(102),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),
|
||||||
char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(50),
|
char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),
|
||||||
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),
|
char(112),char(114),char(105),char(110),char(103),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(50),char(0),char(98),char(116),char(83),char(108),char(105),char(100),char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),
|
char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(67),
|
||||||
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(108),char(105),char(100),char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),
|
char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),
|
||||||
char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(97),char(114),
|
char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),
|
||||||
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),
|
char(50),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),
|
||||||
char(98),char(116),char(71),char(101),char(97),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),
|
char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(50),char(67),char(111),char(110),char(115),
|
||||||
char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(77),char(97),char(116),char(101),char(114),
|
char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),
|
||||||
char(105),char(97),char(108),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(78),char(111),char(100),char(101),
|
char(83),char(108),char(105),char(100),char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),
|
||||||
char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(97),char(116),
|
char(0),char(98),char(116),char(83),char(108),char(105),char(100),char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),
|
||||||
char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(70),char(97),char(99),char(101),char(68),char(97),char(116),char(97),char(0),char(83),
|
char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(97),char(114),char(67),char(111),char(110),char(115),
|
||||||
char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(84),char(101),char(116),char(114),char(97),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),
|
char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),
|
||||||
char(116),char(82),char(105),char(103),char(105),char(100),char(65),char(110),char(99),char(104),char(111),char(114),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),
|
char(97),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),
|
||||||
char(116),char(66),char(111),char(100),char(121),char(67),char(111),char(110),char(102),char(105),char(103),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),
|
char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(77),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(68),
|
||||||
char(66),char(111),char(100),char(121),char(80),char(111),char(115),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),
|
char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(78),char(111),char(100),char(101),char(68),char(97),char(116),char(97),
|
||||||
char(121),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66),
|
char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(97),char(116),char(97),char(0),char(83),char(111),
|
||||||
char(111),char(100),char(121),char(74),char(111),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66),
|
char(102),char(116),char(66),char(111),char(100),char(121),char(70),char(97),char(99),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),
|
||||||
char(111),char(100),char(121),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),
|
char(111),char(100),char(121),char(84),char(101),char(116),char(114),char(97),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(82),char(105),char(103),
|
||||||
char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),
|
char(105),char(100),char(65),char(110),char(99),char(104),char(111),char(114),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),
|
||||||
char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(70),char(108),char(111),char(97),char(116),char(68),
|
char(121),char(67),char(111),char(110),char(102),char(105),char(103),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(68),char(111),char(117),char(98),char(108),
|
char(80),char(111),char(115),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(67),char(108),char(117),
|
||||||
char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(70),char(108),char(111),
|
char(115),char(116),char(101),char(114),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(74),
|
||||||
char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(0),char(84),char(76),char(69),char(78),char(1),char(0),char(1),char(0),char(2),char(0),char(2),char(0),
|
char(111),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(70),
|
||||||
char(4),char(0),char(4),char(0),char(4),char(0),char(4),char(0),char(8),char(0),char(0),char(0),char(12),char(0),char(36),char(0),char(8),char(0),char(16),char(0),
|
char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),
|
||||||
char(32),char(0),char(16),char(0),char(32),char(0),char(48),char(0),char(96),char(0),char(64),char(0),char(-128),char(0),char(20),char(0),char(48),char(0),char(80),char(0),
|
char(76),char(105),char(110),char(107),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),
|
||||||
char(16),char(0),char(84),char(0),char(-124),char(0),char(12),char(0),char(52),char(0),char(52),char(0),char(20),char(0),char(64),char(0),char(4),char(0),char(4),char(0),
|
char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(8),char(0),char(4),char(0),char(32),char(0),char(28),char(0),char(60),char(0),char(56),char(0),char(76),char(0),char(76),char(0),char(24),char(0),char(60),char(0),
|
char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),
|
||||||
char(60),char(0),char(60),char(0),char(16),char(0),char(64),char(0),char(68),char(0),char(-32),char(1),char(8),char(1),char(-104),char(0),char(88),char(0),char(-72),char(0),
|
char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(70),char(108),char(111),char(97),char(116),char(68),char(97),
|
||||||
char(104),char(0),char(-16),char(1),char(-80),char(3),char(8),char(0),char(52),char(0),char(52),char(0),char(0),char(0),char(68),char(0),char(84),char(0),char(-124),char(0),
|
char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(67),char(111),
|
||||||
char(116),char(0),char(92),char(1),char(-36),char(0),char(-116),char(1),char(124),char(1),char(-44),char(0),char(-4),char(0),char(-52),char(1),char(92),char(1),char(116),char(2),
|
char(108),char(108),char(105),char(100),char(101),char(114),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),
|
||||||
char(-124),char(2),char(-76),char(4),char(-52),char(0),char(108),char(1),char(92),char(0),char(-116),char(0),char(16),char(0),char(100),char(0),char(20),char(0),char(36),char(0),
|
char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(68),
|
||||||
char(100),char(0),char(92),char(0),char(104),char(0),char(-64),char(0),char(92),char(1),char(104),char(0),char(-76),char(1),char(-16),char(2),char(-120),char(1),char(-64),char(0),
|
char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(0),char(0),char(84),char(76),char(69),char(78),char(1),char(0),char(1),char(0),
|
||||||
char(100),char(0),char(0),char(0),char(83),char(84),char(82),char(67),char(84),char(0),char(0),char(0),char(10),char(0),char(3),char(0),char(4),char(0),char(0),char(0),
|
char(2),char(0),char(2),char(0),char(4),char(0),char(4),char(0),char(4),char(0),char(4),char(0),char(8),char(0),char(0),char(0),char(12),char(0),char(36),char(0),
|
||||||
char(4),char(0),char(1),char(0),char(9),char(0),char(2),char(0),char(11),char(0),char(3),char(0),char(10),char(0),char(3),char(0),char(10),char(0),char(4),char(0),
|
char(8),char(0),char(16),char(0),char(32),char(0),char(16),char(0),char(32),char(0),char(48),char(0),char(96),char(0),char(64),char(0),char(-128),char(0),char(20),char(0),
|
||||||
char(10),char(0),char(5),char(0),char(12),char(0),char(2),char(0),char(9),char(0),char(6),char(0),char(9),char(0),char(7),char(0),char(13),char(0),char(1),char(0),
|
char(48),char(0),char(80),char(0),char(16),char(0),char(84),char(0),char(-124),char(0),char(12),char(0),char(52),char(0),char(52),char(0),char(20),char(0),char(64),char(0),
|
||||||
char(7),char(0),char(8),char(0),char(14),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(15),char(0),char(1),char(0),char(7),char(0),char(8),char(0),
|
char(4),char(0),char(4),char(0),char(8),char(0),char(4),char(0),char(32),char(0),char(28),char(0),char(60),char(0),char(56),char(0),char(76),char(0),char(76),char(0),
|
||||||
char(16),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(17),char(0),char(1),char(0),char(13),char(0),char(9),char(0),char(18),char(0),char(1),char(0),
|
char(24),char(0),char(60),char(0),char(60),char(0),char(60),char(0),char(16),char(0),char(64),char(0),char(68),char(0),char(-32),char(1),char(8),char(1),char(-104),char(0),
|
||||||
char(14),char(0),char(9),char(0),char(19),char(0),char(2),char(0),char(17),char(0),char(10),char(0),char(13),char(0),char(11),char(0),char(20),char(0),char(2),char(0),
|
char(88),char(0),char(-72),char(0),char(104),char(0),char(-16),char(1),char(-80),char(3),char(8),char(0),char(52),char(0),char(52),char(0),char(0),char(0),char(68),char(0),
|
||||||
char(18),char(0),char(10),char(0),char(14),char(0),char(11),char(0),char(21),char(0),char(4),char(0),char(4),char(0),char(12),char(0),char(4),char(0),char(13),char(0),
|
char(84),char(0),char(-124),char(0),char(116),char(0),char(92),char(1),char(-36),char(0),char(-116),char(1),char(124),char(1),char(-44),char(0),char(-4),char(0),char(-52),char(1),
|
||||||
char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0),char(22),char(0),char(6),char(0),char(13),char(0),char(16),char(0),char(13),char(0),char(17),char(0),
|
char(92),char(1),char(116),char(2),char(-124),char(2),char(-76),char(4),char(-52),char(0),char(108),char(1),char(92),char(0),char(-116),char(0),char(16),char(0),char(100),char(0),
|
||||||
char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0),char(0),char(0),char(21),char(0),char(23),char(0),char(6),char(0),
|
char(20),char(0),char(36),char(0),char(100),char(0),char(92),char(0),char(104),char(0),char(-64),char(0),char(92),char(1),char(104),char(0),char(-76),char(1),char(-16),char(2),
|
||||||
char(14),char(0),char(16),char(0),char(14),char(0),char(17),char(0),char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0),
|
char(-120),char(1),char(-64),char(0),char(100),char(0),char(20),char(1),char(-20),char(1),char(0),char(0),char(83),char(84),char(82),char(67),char(86),char(0),char(0),char(0),
|
||||||
char(0),char(0),char(21),char(0),char(24),char(0),char(3),char(0),char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0),char(4),char(0),char(22),char(0),
|
char(10),char(0),char(3),char(0),char(4),char(0),char(0),char(0),char(4),char(0),char(1),char(0),char(9),char(0),char(2),char(0),char(11),char(0),char(3),char(0),
|
||||||
char(25),char(0),char(12),char(0),char(13),char(0),char(23),char(0),char(13),char(0),char(24),char(0),char(13),char(0),char(25),char(0),char(4),char(0),char(26),char(0),
|
char(10),char(0),char(3),char(0),char(10),char(0),char(4),char(0),char(10),char(0),char(5),char(0),char(12),char(0),char(2),char(0),char(9),char(0),char(6),char(0),
|
||||||
char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0),char(4),char(0),char(29),char(0),char(22),char(0),char(30),char(0),char(24),char(0),char(31),char(0),
|
char(9),char(0),char(7),char(0),char(13),char(0),char(1),char(0),char(7),char(0),char(8),char(0),char(14),char(0),char(1),char(0),char(8),char(0),char(8),char(0),
|
||||||
char(21),char(0),char(32),char(0),char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0),char(26),char(0),char(12),char(0),char(14),char(0),char(23),char(0),
|
char(15),char(0),char(1),char(0),char(7),char(0),char(8),char(0),char(16),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(17),char(0),char(1),char(0),
|
||||||
char(14),char(0),char(24),char(0),char(14),char(0),char(25),char(0),char(4),char(0),char(26),char(0),char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0),
|
char(13),char(0),char(9),char(0),char(18),char(0),char(1),char(0),char(14),char(0),char(9),char(0),char(19),char(0),char(2),char(0),char(17),char(0),char(10),char(0),
|
||||||
char(4),char(0),char(29),char(0),char(23),char(0),char(30),char(0),char(24),char(0),char(31),char(0),char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0),
|
char(13),char(0),char(11),char(0),char(20),char(0),char(2),char(0),char(18),char(0),char(10),char(0),char(14),char(0),char(11),char(0),char(21),char(0),char(4),char(0),
|
||||||
char(21),char(0),char(32),char(0),char(27),char(0),char(3),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(36),char(0),char(0),char(0),char(37),char(0),
|
char(4),char(0),char(12),char(0),char(4),char(0),char(13),char(0),char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0),char(22),char(0),char(6),char(0),
|
||||||
char(28),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0),char(13),char(0),char(40),char(0),char(7),char(0),char(41),char(0),
|
char(13),char(0),char(16),char(0),char(13),char(0),char(17),char(0),char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0),
|
||||||
char(0),char(0),char(21),char(0),char(29),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0),char(13),char(0),char(42),char(0),
|
char(0),char(0),char(21),char(0),char(23),char(0),char(6),char(0),char(14),char(0),char(16),char(0),char(14),char(0),char(17),char(0),char(4),char(0),char(18),char(0),
|
||||||
char(7),char(0),char(43),char(0),char(4),char(0),char(44),char(0),char(30),char(0),char(2),char(0),char(13),char(0),char(45),char(0),char(7),char(0),char(46),char(0),
|
char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0),char(0),char(0),char(21),char(0),char(24),char(0),char(3),char(0),char(2),char(0),char(14),char(0),
|
||||||
char(31),char(0),char(4),char(0),char(29),char(0),char(47),char(0),char(30),char(0),char(48),char(0),char(4),char(0),char(49),char(0),char(0),char(0),char(37),char(0),
|
char(2),char(0),char(15),char(0),char(4),char(0),char(22),char(0),char(25),char(0),char(12),char(0),char(13),char(0),char(23),char(0),char(13),char(0),char(24),char(0),
|
||||||
char(32),char(0),char(1),char(0),char(4),char(0),char(50),char(0),char(33),char(0),char(2),char(0),char(2),char(0),char(50),char(0),char(0),char(0),char(51),char(0),
|
char(13),char(0),char(25),char(0),char(4),char(0),char(26),char(0),char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0),char(4),char(0),char(29),char(0),
|
||||||
char(34),char(0),char(2),char(0),char(2),char(0),char(52),char(0),char(0),char(0),char(51),char(0),char(35),char(0),char(2),char(0),char(0),char(0),char(52),char(0),
|
char(22),char(0),char(30),char(0),char(24),char(0),char(31),char(0),char(21),char(0),char(32),char(0),char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0),
|
||||||
char(0),char(0),char(53),char(0),char(36),char(0),char(8),char(0),char(13),char(0),char(54),char(0),char(14),char(0),char(55),char(0),char(32),char(0),char(56),char(0),
|
char(26),char(0),char(12),char(0),char(14),char(0),char(23),char(0),char(14),char(0),char(24),char(0),char(14),char(0),char(25),char(0),char(4),char(0),char(26),char(0),
|
||||||
char(34),char(0),char(57),char(0),char(35),char(0),char(58),char(0),char(33),char(0),char(59),char(0),char(4),char(0),char(60),char(0),char(4),char(0),char(61),char(0),
|
char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0),char(4),char(0),char(29),char(0),char(23),char(0),char(30),char(0),char(24),char(0),char(31),char(0),
|
||||||
char(37),char(0),char(4),char(0),char(36),char(0),char(62),char(0),char(13),char(0),char(63),char(0),char(4),char(0),char(64),char(0),char(0),char(0),char(37),char(0),
|
char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0),char(21),char(0),char(32),char(0),char(27),char(0),char(3),char(0),char(0),char(0),char(35),char(0),
|
||||||
char(38),char(0),char(7),char(0),char(27),char(0),char(38),char(0),char(37),char(0),char(65),char(0),char(25),char(0),char(66),char(0),char(26),char(0),char(67),char(0),
|
char(4),char(0),char(36),char(0),char(0),char(0),char(37),char(0),char(28),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0),
|
||||||
char(39),char(0),char(68),char(0),char(7),char(0),char(43),char(0),char(0),char(0),char(69),char(0),char(40),char(0),char(2),char(0),char(38),char(0),char(70),char(0),
|
char(13),char(0),char(40),char(0),char(7),char(0),char(41),char(0),char(0),char(0),char(21),char(0),char(29),char(0),char(5),char(0),char(27),char(0),char(38),char(0),
|
||||||
char(13),char(0),char(39),char(0),char(41),char(0),char(4),char(0),char(19),char(0),char(71),char(0),char(27),char(0),char(72),char(0),char(4),char(0),char(73),char(0),
|
char(13),char(0),char(39),char(0),char(13),char(0),char(42),char(0),char(7),char(0),char(43),char(0),char(4),char(0),char(44),char(0),char(30),char(0),char(2),char(0),
|
||||||
char(7),char(0),char(74),char(0),char(42),char(0),char(4),char(0),char(27),char(0),char(38),char(0),char(41),char(0),char(75),char(0),char(4),char(0),char(76),char(0),
|
char(13),char(0),char(45),char(0),char(7),char(0),char(46),char(0),char(31),char(0),char(4),char(0),char(29),char(0),char(47),char(0),char(30),char(0),char(48),char(0),
|
||||||
char(7),char(0),char(43),char(0),char(43),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0),
|
char(4),char(0),char(49),char(0),char(0),char(0),char(37),char(0),char(32),char(0),char(1),char(0),char(4),char(0),char(50),char(0),char(33),char(0),char(2),char(0),
|
||||||
char(44),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(78),char(0),char(0),char(0),char(37),char(0),char(45),char(0),char(3),char(0),
|
char(2),char(0),char(50),char(0),char(0),char(0),char(51),char(0),char(34),char(0),char(2),char(0),char(2),char(0),char(52),char(0),char(0),char(0),char(51),char(0),
|
||||||
char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0),char(46),char(0),char(4),char(0),char(4),char(0),char(79),char(0),
|
char(35),char(0),char(2),char(0),char(0),char(0),char(52),char(0),char(0),char(0),char(53),char(0),char(36),char(0),char(8),char(0),char(13),char(0),char(54),char(0),
|
||||||
char(7),char(0),char(80),char(0),char(7),char(0),char(81),char(0),char(7),char(0),char(82),char(0),char(39),char(0),char(14),char(0),char(4),char(0),char(83),char(0),
|
char(14),char(0),char(55),char(0),char(32),char(0),char(56),char(0),char(34),char(0),char(57),char(0),char(35),char(0),char(58),char(0),char(33),char(0),char(59),char(0),
|
||||||
char(4),char(0),char(84),char(0),char(46),char(0),char(85),char(0),char(4),char(0),char(86),char(0),char(7),char(0),char(87),char(0),char(7),char(0),char(88),char(0),
|
char(4),char(0),char(60),char(0),char(4),char(0),char(61),char(0),char(37),char(0),char(4),char(0),char(36),char(0),char(62),char(0),char(13),char(0),char(63),char(0),
|
||||||
char(7),char(0),char(89),char(0),char(7),char(0),char(90),char(0),char(7),char(0),char(91),char(0),char(4),char(0),char(92),char(0),char(4),char(0),char(93),char(0),
|
char(4),char(0),char(64),char(0),char(0),char(0),char(37),char(0),char(38),char(0),char(7),char(0),char(27),char(0),char(38),char(0),char(37),char(0),char(65),char(0),
|
||||||
char(4),char(0),char(94),char(0),char(4),char(0),char(95),char(0),char(0),char(0),char(37),char(0),char(47),char(0),char(5),char(0),char(27),char(0),char(38),char(0),
|
char(25),char(0),char(66),char(0),char(26),char(0),char(67),char(0),char(39),char(0),char(68),char(0),char(7),char(0),char(43),char(0),char(0),char(0),char(69),char(0),
|
||||||
char(37),char(0),char(65),char(0),char(13),char(0),char(39),char(0),char(7),char(0),char(43),char(0),char(4),char(0),char(96),char(0),char(48),char(0),char(5),char(0),
|
char(40),char(0),char(2),char(0),char(38),char(0),char(70),char(0),char(13),char(0),char(39),char(0),char(41),char(0),char(4),char(0),char(19),char(0),char(71),char(0),
|
||||||
char(29),char(0),char(47),char(0),char(13),char(0),char(97),char(0),char(14),char(0),char(98),char(0),char(4),char(0),char(99),char(0),char(0),char(0),char(100),char(0),
|
char(27),char(0),char(72),char(0),char(4),char(0),char(73),char(0),char(7),char(0),char(74),char(0),char(42),char(0),char(4),char(0),char(27),char(0),char(38),char(0),
|
||||||
char(49),char(0),char(27),char(0),char(9),char(0),char(101),char(0),char(9),char(0),char(102),char(0),char(27),char(0),char(103),char(0),char(0),char(0),char(35),char(0),
|
char(41),char(0),char(75),char(0),char(4),char(0),char(76),char(0),char(7),char(0),char(43),char(0),char(43),char(0),char(3),char(0),char(29),char(0),char(47),char(0),
|
||||||
char(20),char(0),char(104),char(0),char(20),char(0),char(105),char(0),char(14),char(0),char(106),char(0),char(14),char(0),char(107),char(0),char(14),char(0),char(108),char(0),
|
char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0),char(44),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(78),char(0),
|
||||||
char(8),char(0),char(109),char(0),char(8),char(0),char(110),char(0),char(8),char(0),char(111),char(0),char(8),char(0),char(112),char(0),char(8),char(0),char(113),char(0),
|
char(0),char(0),char(37),char(0),char(45),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0),
|
||||||
char(8),char(0),char(114),char(0),char(8),char(0),char(115),char(0),char(8),char(0),char(116),char(0),char(8),char(0),char(117),char(0),char(8),char(0),char(118),char(0),
|
char(46),char(0),char(4),char(0),char(4),char(0),char(79),char(0),char(7),char(0),char(80),char(0),char(7),char(0),char(81),char(0),char(7),char(0),char(82),char(0),
|
||||||
|
char(39),char(0),char(14),char(0),char(4),char(0),char(83),char(0),char(4),char(0),char(84),char(0),char(46),char(0),char(85),char(0),char(4),char(0),char(86),char(0),
|
||||||
|
char(7),char(0),char(87),char(0),char(7),char(0),char(88),char(0),char(7),char(0),char(89),char(0),char(7),char(0),char(90),char(0),char(7),char(0),char(91),char(0),
|
||||||
|
char(4),char(0),char(92),char(0),char(4),char(0),char(93),char(0),char(4),char(0),char(94),char(0),char(4),char(0),char(95),char(0),char(0),char(0),char(37),char(0),
|
||||||
|
char(47),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(37),char(0),char(65),char(0),char(13),char(0),char(39),char(0),char(7),char(0),char(43),char(0),
|
||||||
|
char(4),char(0),char(96),char(0),char(48),char(0),char(5),char(0),char(29),char(0),char(47),char(0),char(13),char(0),char(97),char(0),char(14),char(0),char(98),char(0),
|
||||||
|
char(4),char(0),char(99),char(0),char(0),char(0),char(100),char(0),char(49),char(0),char(27),char(0),char(9),char(0),char(101),char(0),char(9),char(0),char(102),char(0),
|
||||||
|
char(27),char(0),char(103),char(0),char(0),char(0),char(35),char(0),char(20),char(0),char(104),char(0),char(20),char(0),char(105),char(0),char(14),char(0),char(106),char(0),
|
||||||
|
char(14),char(0),char(107),char(0),char(14),char(0),char(108),char(0),char(8),char(0),char(109),char(0),char(8),char(0),char(110),char(0),char(8),char(0),char(111),char(0),
|
||||||
|
char(8),char(0),char(112),char(0),char(8),char(0),char(113),char(0),char(8),char(0),char(114),char(0),char(8),char(0),char(115),char(0),char(8),char(0),char(116),char(0),
|
||||||
|
char(8),char(0),char(117),char(0),char(8),char(0),char(118),char(0),char(4),char(0),char(119),char(0),char(4),char(0),char(120),char(0),char(4),char(0),char(121),char(0),
|
||||||
|
char(4),char(0),char(122),char(0),char(4),char(0),char(123),char(0),char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0),char(0),char(0),char(37),char(0),
|
||||||
|
char(50),char(0),char(27),char(0),char(9),char(0),char(101),char(0),char(9),char(0),char(102),char(0),char(27),char(0),char(103),char(0),char(0),char(0),char(35),char(0),
|
||||||
|
char(19),char(0),char(104),char(0),char(19),char(0),char(105),char(0),char(13),char(0),char(106),char(0),char(13),char(0),char(107),char(0),char(13),char(0),char(108),char(0),
|
||||||
|
char(7),char(0),char(109),char(0),char(7),char(0),char(110),char(0),char(7),char(0),char(111),char(0),char(7),char(0),char(112),char(0),char(7),char(0),char(113),char(0),
|
||||||
|
char(7),char(0),char(114),char(0),char(7),char(0),char(115),char(0),char(7),char(0),char(116),char(0),char(7),char(0),char(117),char(0),char(7),char(0),char(118),char(0),
|
||||||
char(4),char(0),char(119),char(0),char(4),char(0),char(120),char(0),char(4),char(0),char(121),char(0),char(4),char(0),char(122),char(0),char(4),char(0),char(123),char(0),
|
char(4),char(0),char(119),char(0),char(4),char(0),char(120),char(0),char(4),char(0),char(121),char(0),char(4),char(0),char(122),char(0),char(4),char(0),char(123),char(0),
|
||||||
char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0),char(0),char(0),char(37),char(0),char(50),char(0),char(27),char(0),char(9),char(0),char(101),char(0),
|
char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0),char(0),char(0),char(37),char(0),char(51),char(0),char(22),char(0),char(8),char(0),char(126),char(0),
|
||||||
char(9),char(0),char(102),char(0),char(27),char(0),char(103),char(0),char(0),char(0),char(35),char(0),char(19),char(0),char(104),char(0),char(19),char(0),char(105),char(0),
|
char(8),char(0),char(127),char(0),char(8),char(0),char(111),char(0),char(8),char(0),char(-128),char(0),char(8),char(0),char(115),char(0),char(8),char(0),char(-127),char(0),
|
||||||
char(13),char(0),char(106),char(0),char(13),char(0),char(107),char(0),char(13),char(0),char(108),char(0),char(7),char(0),char(109),char(0),char(7),char(0),char(110),char(0),
|
char(8),char(0),char(-126),char(0),char(8),char(0),char(-125),char(0),char(8),char(0),char(-124),char(0),char(8),char(0),char(-123),char(0),char(8),char(0),char(-122),char(0),
|
||||||
char(7),char(0),char(111),char(0),char(7),char(0),char(112),char(0),char(7),char(0),char(113),char(0),char(7),char(0),char(114),char(0),char(7),char(0),char(115),char(0),
|
char(8),char(0),char(-121),char(0),char(8),char(0),char(-120),char(0),char(8),char(0),char(-119),char(0),char(8),char(0),char(-118),char(0),char(8),char(0),char(-117),char(0),
|
||||||
char(7),char(0),char(116),char(0),char(7),char(0),char(117),char(0),char(7),char(0),char(118),char(0),char(4),char(0),char(119),char(0),char(4),char(0),char(120),char(0),
|
char(4),char(0),char(-116),char(0),char(4),char(0),char(-115),char(0),char(4),char(0),char(-114),char(0),char(4),char(0),char(-113),char(0),char(4),char(0),char(-112),char(0),
|
||||||
char(4),char(0),char(121),char(0),char(4),char(0),char(122),char(0),char(4),char(0),char(123),char(0),char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0),
|
char(0),char(0),char(37),char(0),char(52),char(0),char(22),char(0),char(7),char(0),char(126),char(0),char(7),char(0),char(127),char(0),char(7),char(0),char(111),char(0),
|
||||||
char(0),char(0),char(37),char(0),char(51),char(0),char(22),char(0),char(8),char(0),char(126),char(0),char(8),char(0),char(127),char(0),char(8),char(0),char(111),char(0),
|
char(7),char(0),char(-128),char(0),char(7),char(0),char(115),char(0),char(7),char(0),char(-127),char(0),char(7),char(0),char(-126),char(0),char(7),char(0),char(-125),char(0),
|
||||||
char(8),char(0),char(-128),char(0),char(8),char(0),char(115),char(0),char(8),char(0),char(-127),char(0),char(8),char(0),char(-126),char(0),char(8),char(0),char(-125),char(0),
|
char(7),char(0),char(-124),char(0),char(7),char(0),char(-123),char(0),char(7),char(0),char(-122),char(0),char(7),char(0),char(-121),char(0),char(7),char(0),char(-120),char(0),
|
||||||
char(8),char(0),char(-124),char(0),char(8),char(0),char(-123),char(0),char(8),char(0),char(-122),char(0),char(8),char(0),char(-121),char(0),char(8),char(0),char(-120),char(0),
|
char(7),char(0),char(-119),char(0),char(7),char(0),char(-118),char(0),char(7),char(0),char(-117),char(0),char(4),char(0),char(-116),char(0),char(4),char(0),char(-115),char(0),
|
||||||
char(8),char(0),char(-119),char(0),char(8),char(0),char(-118),char(0),char(8),char(0),char(-117),char(0),char(4),char(0),char(-116),char(0),char(4),char(0),char(-115),char(0),
|
char(4),char(0),char(-114),char(0),char(4),char(0),char(-113),char(0),char(4),char(0),char(-112),char(0),char(0),char(0),char(37),char(0),char(53),char(0),char(2),char(0),
|
||||||
char(4),char(0),char(-114),char(0),char(4),char(0),char(-113),char(0),char(4),char(0),char(-112),char(0),char(0),char(0),char(37),char(0),char(52),char(0),char(22),char(0),
|
char(51),char(0),char(-111),char(0),char(14),char(0),char(-110),char(0),char(54),char(0),char(2),char(0),char(52),char(0),char(-111),char(0),char(13),char(0),char(-110),char(0),
|
||||||
char(7),char(0),char(126),char(0),char(7),char(0),char(127),char(0),char(7),char(0),char(111),char(0),char(7),char(0),char(-128),char(0),char(7),char(0),char(115),char(0),
|
char(55),char(0),char(21),char(0),char(50),char(0),char(-109),char(0),char(17),char(0),char(-108),char(0),char(13),char(0),char(-107),char(0),char(13),char(0),char(-106),char(0),
|
||||||
char(7),char(0),char(-127),char(0),char(7),char(0),char(-126),char(0),char(7),char(0),char(-125),char(0),char(7),char(0),char(-124),char(0),char(7),char(0),char(-123),char(0),
|
char(13),char(0),char(-105),char(0),char(13),char(0),char(-104),char(0),char(13),char(0),char(-110),char(0),char(13),char(0),char(-103),char(0),char(13),char(0),char(-102),char(0),
|
||||||
char(7),char(0),char(-122),char(0),char(7),char(0),char(-121),char(0),char(7),char(0),char(-120),char(0),char(7),char(0),char(-119),char(0),char(7),char(0),char(-118),char(0),
|
char(13),char(0),char(-101),char(0),char(13),char(0),char(-100),char(0),char(7),char(0),char(-99),char(0),char(7),char(0),char(-98),char(0),char(7),char(0),char(-97),char(0),
|
||||||
char(7),char(0),char(-117),char(0),char(4),char(0),char(-116),char(0),char(4),char(0),char(-115),char(0),char(4),char(0),char(-114),char(0),char(4),char(0),char(-113),char(0),
|
char(7),char(0),char(-96),char(0),char(7),char(0),char(-95),char(0),char(7),char(0),char(-94),char(0),char(7),char(0),char(-93),char(0),char(7),char(0),char(-92),char(0),
|
||||||
char(4),char(0),char(-112),char(0),char(0),char(0),char(37),char(0),char(53),char(0),char(2),char(0),char(51),char(0),char(-111),char(0),char(14),char(0),char(-110),char(0),
|
char(7),char(0),char(-91),char(0),char(4),char(0),char(-90),char(0),char(56),char(0),char(22),char(0),char(49),char(0),char(-109),char(0),char(18),char(0),char(-108),char(0),
|
||||||
char(54),char(0),char(2),char(0),char(52),char(0),char(-111),char(0),char(13),char(0),char(-110),char(0),char(55),char(0),char(21),char(0),char(50),char(0),char(-109),char(0),
|
char(14),char(0),char(-107),char(0),char(14),char(0),char(-106),char(0),char(14),char(0),char(-105),char(0),char(14),char(0),char(-104),char(0),char(14),char(0),char(-110),char(0),
|
||||||
char(17),char(0),char(-108),char(0),char(13),char(0),char(-107),char(0),char(13),char(0),char(-106),char(0),char(13),char(0),char(-105),char(0),char(13),char(0),char(-104),char(0),
|
char(14),char(0),char(-103),char(0),char(14),char(0),char(-102),char(0),char(14),char(0),char(-101),char(0),char(14),char(0),char(-100),char(0),char(8),char(0),char(-99),char(0),
|
||||||
char(13),char(0),char(-110),char(0),char(13),char(0),char(-103),char(0),char(13),char(0),char(-102),char(0),char(13),char(0),char(-101),char(0),char(13),char(0),char(-100),char(0),
|
char(8),char(0),char(-98),char(0),char(8),char(0),char(-97),char(0),char(8),char(0),char(-96),char(0),char(8),char(0),char(-95),char(0),char(8),char(0),char(-94),char(0),
|
||||||
char(7),char(0),char(-99),char(0),char(7),char(0),char(-98),char(0),char(7),char(0),char(-97),char(0),char(7),char(0),char(-96),char(0),char(7),char(0),char(-95),char(0),
|
char(8),char(0),char(-93),char(0),char(8),char(0),char(-92),char(0),char(8),char(0),char(-91),char(0),char(4),char(0),char(-90),char(0),char(0),char(0),char(37),char(0),
|
||||||
char(7),char(0),char(-94),char(0),char(7),char(0),char(-93),char(0),char(7),char(0),char(-92),char(0),char(7),char(0),char(-91),char(0),char(4),char(0),char(-90),char(0),
|
char(57),char(0),char(2),char(0),char(4),char(0),char(-89),char(0),char(4),char(0),char(-88),char(0),char(58),char(0),char(13),char(0),char(55),char(0),char(-87),char(0),
|
||||||
char(56),char(0),char(22),char(0),char(49),char(0),char(-109),char(0),char(18),char(0),char(-108),char(0),char(14),char(0),char(-107),char(0),char(14),char(0),char(-106),char(0),
|
char(55),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),
|
||||||
char(14),char(0),char(-105),char(0),char(14),char(0),char(-104),char(0),char(14),char(0),char(-110),char(0),char(14),char(0),char(-103),char(0),char(14),char(0),char(-102),char(0),
|
char(4),char(0),char(-82),char(0),char(7),char(0),char(-81),char(0),char(7),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),
|
||||||
char(14),char(0),char(-101),char(0),char(14),char(0),char(-100),char(0),char(8),char(0),char(-99),char(0),char(8),char(0),char(-98),char(0),char(8),char(0),char(-97),char(0),
|
char(7),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),char(59),char(0),char(13),char(0),char(60),char(0),char(-87),char(0),char(60),char(0),char(-86),char(0),
|
||||||
char(8),char(0),char(-96),char(0),char(8),char(0),char(-95),char(0),char(8),char(0),char(-94),char(0),char(8),char(0),char(-93),char(0),char(8),char(0),char(-92),char(0),
|
char(0),char(0),char(35),char(0),char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),
|
||||||
char(8),char(0),char(-91),char(0),char(4),char(0),char(-90),char(0),char(0),char(0),char(37),char(0),char(57),char(0),char(2),char(0),char(4),char(0),char(-89),char(0),
|
char(7),char(0),char(-81),char(0),char(7),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),char(7),char(0),char(-77),char(0),
|
||||||
char(4),char(0),char(-88),char(0),char(58),char(0),char(13),char(0),char(55),char(0),char(-87),char(0),char(55),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),
|
char(4),char(0),char(-76),char(0),char(61),char(0),char(14),char(0),char(56),char(0),char(-87),char(0),char(56),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),
|
||||||
char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(7),char(0),char(-81),char(0),
|
char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(8),char(0),char(-81),char(0),
|
||||||
char(7),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),char(7),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),
|
char(8),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),char(8),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),
|
||||||
char(59),char(0),char(13),char(0),char(60),char(0),char(-87),char(0),char(60),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-85),char(0),
|
char(0),char(0),char(-75),char(0),char(62),char(0),char(3),char(0),char(59),char(0),char(-74),char(0),char(13),char(0),char(-73),char(0),char(13),char(0),char(-72),char(0),
|
||||||
char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(7),char(0),char(-81),char(0),char(7),char(0),char(-80),char(0),
|
char(63),char(0),char(3),char(0),char(61),char(0),char(-74),char(0),char(14),char(0),char(-73),char(0),char(14),char(0),char(-72),char(0),char(64),char(0),char(3),char(0),
|
||||||
char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),char(7),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),char(61),char(0),char(14),char(0),
|
char(59),char(0),char(-74),char(0),char(14),char(0),char(-73),char(0),char(14),char(0),char(-72),char(0),char(65),char(0),char(13),char(0),char(59),char(0),char(-74),char(0),
|
||||||
char(56),char(0),char(-87),char(0),char(56),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0),
|
char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),
|
||||||
char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(8),char(0),char(-81),char(0),char(8),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0),
|
char(7),char(0),char(-66),char(0),char(7),char(0),char(-65),char(0),char(7),char(0),char(-64),char(0),char(7),char(0),char(-63),char(0),char(7),char(0),char(-62),char(0),
|
||||||
char(4),char(0),char(-78),char(0),char(8),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),char(0),char(0),char(-75),char(0),char(62),char(0),char(3),char(0),
|
char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),char(66),char(0),char(13),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),
|
||||||
char(59),char(0),char(-74),char(0),char(13),char(0),char(-73),char(0),char(13),char(0),char(-72),char(0),char(63),char(0),char(3),char(0),char(61),char(0),char(-74),char(0),
|
char(19),char(0),char(-70),char(0),char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),char(7),char(0),char(-66),char(0),
|
||||||
char(14),char(0),char(-73),char(0),char(14),char(0),char(-72),char(0),char(64),char(0),char(3),char(0),char(59),char(0),char(-74),char(0),char(14),char(0),char(-73),char(0),
|
char(7),char(0),char(-65),char(0),char(7),char(0),char(-64),char(0),char(7),char(0),char(-63),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),
|
||||||
char(14),char(0),char(-72),char(0),char(65),char(0),char(13),char(0),char(59),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),
|
char(7),char(0),char(-60),char(0),char(67),char(0),char(14),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),
|
||||||
char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),char(7),char(0),char(-66),char(0),char(7),char(0),char(-65),char(0),
|
char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),char(8),char(0),char(-66),char(0),char(8),char(0),char(-65),char(0),
|
||||||
char(7),char(0),char(-64),char(0),char(7),char(0),char(-63),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),
|
char(8),char(0),char(-64),char(0),char(8),char(0),char(-63),char(0),char(8),char(0),char(-62),char(0),char(8),char(0),char(-61),char(0),char(8),char(0),char(-60),char(0),
|
||||||
char(66),char(0),char(13),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(4),char(0),char(-69),char(0),
|
char(0),char(0),char(-59),char(0),char(68),char(0),char(10),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),
|
||||||
char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),char(7),char(0),char(-66),char(0),char(7),char(0),char(-65),char(0),char(7),char(0),char(-64),char(0),
|
char(8),char(0),char(-58),char(0),char(8),char(0),char(-57),char(0),char(8),char(0),char(-56),char(0),char(8),char(0),char(-62),char(0),char(8),char(0),char(-61),char(0),
|
||||||
char(7),char(0),char(-63),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),char(67),char(0),char(14),char(0),
|
char(8),char(0),char(-60),char(0),char(8),char(0),char(127),char(0),char(69),char(0),char(11),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),
|
||||||
char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0),
|
char(19),char(0),char(-70),char(0),char(7),char(0),char(-58),char(0),char(7),char(0),char(-57),char(0),char(7),char(0),char(-56),char(0),char(7),char(0),char(-62),char(0),
|
||||||
char(4),char(0),char(-67),char(0),char(8),char(0),char(-66),char(0),char(8),char(0),char(-65),char(0),char(8),char(0),char(-64),char(0),char(8),char(0),char(-63),char(0),
|
char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),char(7),char(0),char(127),char(0),char(0),char(0),char(21),char(0),char(70),char(0),char(9),char(0),
|
||||||
char(8),char(0),char(-62),char(0),char(8),char(0),char(-61),char(0),char(8),char(0),char(-60),char(0),char(0),char(0),char(-59),char(0),char(68),char(0),char(10),char(0),
|
|
||||||
char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(8),char(0),char(-58),char(0),char(8),char(0),char(-57),char(0),
|
|
||||||
char(8),char(0),char(-56),char(0),char(8),char(0),char(-62),char(0),char(8),char(0),char(-61),char(0),char(8),char(0),char(-60),char(0),char(8),char(0),char(127),char(0),
|
|
||||||
char(69),char(0),char(11),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(7),char(0),char(-58),char(0),
|
|
||||||
char(7),char(0),char(-57),char(0),char(7),char(0),char(-56),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),
|
|
||||||
char(7),char(0),char(127),char(0),char(0),char(0),char(21),char(0),char(70),char(0),char(9),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),
|
|
||||||
char(19),char(0),char(-70),char(0),char(13),char(0),char(-55),char(0),char(13),char(0),char(-54),char(0),char(13),char(0),char(-53),char(0),char(13),char(0),char(-52),char(0),
|
|
||||||
char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(71),char(0),char(9),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),
|
|
||||||
char(20),char(0),char(-70),char(0),char(14),char(0),char(-55),char(0),char(14),char(0),char(-54),char(0),char(14),char(0),char(-53),char(0),char(14),char(0),char(-52),char(0),
|
|
||||||
char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(72),char(0),char(5),char(0),char(70),char(0),char(-49),char(0),char(4),char(0),char(-48),char(0),
|
|
||||||
char(7),char(0),char(-47),char(0),char(7),char(0),char(-46),char(0),char(7),char(0),char(-45),char(0),char(73),char(0),char(5),char(0),char(71),char(0),char(-49),char(0),
|
|
||||||
char(4),char(0),char(-48),char(0),char(8),char(0),char(-47),char(0),char(8),char(0),char(-46),char(0),char(8),char(0),char(-45),char(0),char(74),char(0),char(41),char(0),
|
|
||||||
char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(13),char(0),char(-55),char(0),char(13),char(0),char(-54),char(0),
|
char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(13),char(0),char(-55),char(0),char(13),char(0),char(-54),char(0),
|
||||||
char(13),char(0),char(-44),char(0),char(13),char(0),char(-43),char(0),char(13),char(0),char(-42),char(0),char(13),char(0),char(-41),char(0),char(13),char(0),char(-40),char(0),
|
char(13),char(0),char(-53),char(0),char(13),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(71),char(0),char(9),char(0),
|
||||||
char(13),char(0),char(-39),char(0),char(13),char(0),char(-38),char(0),char(13),char(0),char(-37),char(0),char(13),char(0),char(-36),char(0),char(13),char(0),char(-35),char(0),
|
char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(14),char(0),char(-55),char(0),char(14),char(0),char(-54),char(0),
|
||||||
char(13),char(0),char(-34),char(0),char(0),char(0),char(-33),char(0),char(0),char(0),char(-32),char(0),char(0),char(0),char(-31),char(0),char(0),char(0),char(-30),char(0),
|
char(14),char(0),char(-53),char(0),char(14),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(72),char(0),char(5),char(0),
|
||||||
char(0),char(0),char(-29),char(0),char(0),char(0),char(-59),char(0),char(13),char(0),char(-53),char(0),char(13),char(0),char(-52),char(0),char(13),char(0),char(-28),char(0),
|
char(70),char(0),char(-49),char(0),char(4),char(0),char(-48),char(0),char(7),char(0),char(-47),char(0),char(7),char(0),char(-46),char(0),char(7),char(0),char(-45),char(0),
|
||||||
char(13),char(0),char(-27),char(0),char(13),char(0),char(-26),char(0),char(13),char(0),char(-25),char(0),char(13),char(0),char(-24),char(0),char(13),char(0),char(-23),char(0),
|
char(73),char(0),char(5),char(0),char(71),char(0),char(-49),char(0),char(4),char(0),char(-48),char(0),char(8),char(0),char(-47),char(0),char(8),char(0),char(-46),char(0),
|
||||||
char(13),char(0),char(-22),char(0),char(13),char(0),char(-21),char(0),char(13),char(0),char(-20),char(0),char(13),char(0),char(-19),char(0),char(13),char(0),char(-18),char(0),
|
char(8),char(0),char(-45),char(0),char(74),char(0),char(41),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),
|
||||||
char(0),char(0),char(-17),char(0),char(0),char(0),char(-16),char(0),char(0),char(0),char(-15),char(0),char(0),char(0),char(-14),char(0),char(0),char(0),char(-13),char(0),
|
char(13),char(0),char(-55),char(0),char(13),char(0),char(-54),char(0),char(13),char(0),char(-44),char(0),char(13),char(0),char(-43),char(0),char(13),char(0),char(-42),char(0),
|
||||||
char(4),char(0),char(-12),char(0),char(75),char(0),char(41),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),
|
char(13),char(0),char(-41),char(0),char(13),char(0),char(-40),char(0),char(13),char(0),char(-39),char(0),char(13),char(0),char(-38),char(0),char(13),char(0),char(-37),char(0),
|
||||||
char(14),char(0),char(-55),char(0),char(14),char(0),char(-54),char(0),char(14),char(0),char(-44),char(0),char(14),char(0),char(-43),char(0),char(14),char(0),char(-42),char(0),
|
char(13),char(0),char(-36),char(0),char(13),char(0),char(-35),char(0),char(13),char(0),char(-34),char(0),char(0),char(0),char(-33),char(0),char(0),char(0),char(-32),char(0),
|
||||||
char(14),char(0),char(-41),char(0),char(14),char(0),char(-40),char(0),char(14),char(0),char(-39),char(0),char(14),char(0),char(-38),char(0),char(14),char(0),char(-37),char(0),
|
char(0),char(0),char(-31),char(0),char(0),char(0),char(-30),char(0),char(0),char(0),char(-29),char(0),char(0),char(0),char(-59),char(0),char(13),char(0),char(-53),char(0),
|
||||||
char(14),char(0),char(-36),char(0),char(14),char(0),char(-35),char(0),char(14),char(0),char(-34),char(0),char(0),char(0),char(-33),char(0),char(0),char(0),char(-32),char(0),
|
char(13),char(0),char(-52),char(0),char(13),char(0),char(-28),char(0),char(13),char(0),char(-27),char(0),char(13),char(0),char(-26),char(0),char(13),char(0),char(-25),char(0),
|
||||||
char(0),char(0),char(-31),char(0),char(0),char(0),char(-30),char(0),char(0),char(0),char(-29),char(0),char(0),char(0),char(-59),char(0),char(14),char(0),char(-53),char(0),
|
char(13),char(0),char(-24),char(0),char(13),char(0),char(-23),char(0),char(13),char(0),char(-22),char(0),char(13),char(0),char(-21),char(0),char(13),char(0),char(-20),char(0),
|
||||||
char(14),char(0),char(-52),char(0),char(14),char(0),char(-28),char(0),char(14),char(0),char(-27),char(0),char(14),char(0),char(-26),char(0),char(14),char(0),char(-25),char(0),
|
char(13),char(0),char(-19),char(0),char(13),char(0),char(-18),char(0),char(0),char(0),char(-17),char(0),char(0),char(0),char(-16),char(0),char(0),char(0),char(-15),char(0),
|
||||||
char(14),char(0),char(-24),char(0),char(14),char(0),char(-23),char(0),char(14),char(0),char(-22),char(0),char(14),char(0),char(-21),char(0),char(14),char(0),char(-20),char(0),
|
char(0),char(0),char(-14),char(0),char(0),char(0),char(-13),char(0),char(4),char(0),char(-12),char(0),char(75),char(0),char(41),char(0),char(61),char(0),char(-74),char(0),
|
||||||
char(14),char(0),char(-19),char(0),char(14),char(0),char(-18),char(0),char(0),char(0),char(-17),char(0),char(0),char(0),char(-16),char(0),char(0),char(0),char(-15),char(0),
|
char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(14),char(0),char(-55),char(0),char(14),char(0),char(-54),char(0),char(14),char(0),char(-44),char(0),
|
||||||
char(0),char(0),char(-14),char(0),char(0),char(0),char(-13),char(0),char(4),char(0),char(-12),char(0),char(76),char(0),char(9),char(0),char(59),char(0),char(-74),char(0),
|
char(14),char(0),char(-43),char(0),char(14),char(0),char(-42),char(0),char(14),char(0),char(-41),char(0),char(14),char(0),char(-40),char(0),char(14),char(0),char(-39),char(0),
|
||||||
char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(7),char(0),char(-55),char(0),char(7),char(0),char(-54),char(0),char(7),char(0),char(-53),char(0),
|
char(14),char(0),char(-38),char(0),char(14),char(0),char(-37),char(0),char(14),char(0),char(-36),char(0),char(14),char(0),char(-35),char(0),char(14),char(0),char(-34),char(0),
|
||||||
char(7),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(77),char(0),char(9),char(0),char(61),char(0),char(-74),char(0),
|
char(0),char(0),char(-33),char(0),char(0),char(0),char(-32),char(0),char(0),char(0),char(-31),char(0),char(0),char(0),char(-30),char(0),char(0),char(0),char(-29),char(0),
|
||||||
char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(8),char(0),char(-55),char(0),char(8),char(0),char(-54),char(0),char(8),char(0),char(-53),char(0),
|
char(0),char(0),char(-59),char(0),char(14),char(0),char(-53),char(0),char(14),char(0),char(-52),char(0),char(14),char(0),char(-28),char(0),char(14),char(0),char(-27),char(0),
|
||||||
char(8),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(78),char(0),char(5),char(0),char(58),char(0),char(-74),char(0),
|
char(14),char(0),char(-26),char(0),char(14),char(0),char(-25),char(0),char(14),char(0),char(-24),char(0),char(14),char(0),char(-23),char(0),char(14),char(0),char(-22),char(0),
|
||||||
char(13),char(0),char(-11),char(0),char(13),char(0),char(-10),char(0),char(7),char(0),char(-9),char(0),char(0),char(0),char(37),char(0),char(79),char(0),char(4),char(0),
|
char(14),char(0),char(-21),char(0),char(14),char(0),char(-20),char(0),char(14),char(0),char(-19),char(0),char(14),char(0),char(-18),char(0),char(0),char(0),char(-17),char(0),
|
||||||
char(61),char(0),char(-74),char(0),char(14),char(0),char(-11),char(0),char(14),char(0),char(-10),char(0),char(8),char(0),char(-9),char(0),char(80),char(0),char(4),char(0),
|
char(0),char(0),char(-16),char(0),char(0),char(0),char(-15),char(0),char(0),char(0),char(-14),char(0),char(0),char(0),char(-13),char(0),char(4),char(0),char(-12),char(0),
|
||||||
char(7),char(0),char(-8),char(0),char(7),char(0),char(-7),char(0),char(7),char(0),char(-6),char(0),char(4),char(0),char(79),char(0),char(81),char(0),char(10),char(0),
|
char(76),char(0),char(9),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(7),char(0),char(-55),char(0),
|
||||||
char(80),char(0),char(-5),char(0),char(13),char(0),char(-4),char(0),char(13),char(0),char(-3),char(0),char(13),char(0),char(-2),char(0),char(13),char(0),char(-1),char(0),
|
char(7),char(0),char(-54),char(0),char(7),char(0),char(-53),char(0),char(7),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),
|
||||||
char(13),char(0),char(0),char(1),char(7),char(0),char(-99),char(0),char(7),char(0),char(1),char(1),char(4),char(0),char(2),char(1),char(4),char(0),char(53),char(0),
|
char(77),char(0),char(9),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(8),char(0),char(-55),char(0),
|
||||||
char(82),char(0),char(4),char(0),char(80),char(0),char(-5),char(0),char(4),char(0),char(3),char(1),char(7),char(0),char(4),char(1),char(4),char(0),char(5),char(1),
|
char(8),char(0),char(-54),char(0),char(8),char(0),char(-53),char(0),char(8),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),
|
||||||
char(83),char(0),char(4),char(0),char(13),char(0),char(0),char(1),char(80),char(0),char(-5),char(0),char(4),char(0),char(6),char(1),char(7),char(0),char(7),char(1),
|
char(78),char(0),char(5),char(0),char(58),char(0),char(-74),char(0),char(13),char(0),char(-11),char(0),char(13),char(0),char(-10),char(0),char(7),char(0),char(-9),char(0),
|
||||||
char(84),char(0),char(7),char(0),char(13),char(0),char(8),char(1),char(80),char(0),char(-5),char(0),char(4),char(0),char(9),char(1),char(7),char(0),char(10),char(1),
|
char(0),char(0),char(37),char(0),char(79),char(0),char(4),char(0),char(61),char(0),char(-74),char(0),char(14),char(0),char(-11),char(0),char(14),char(0),char(-10),char(0),
|
||||||
char(7),char(0),char(11),char(1),char(7),char(0),char(12),char(1),char(4),char(0),char(53),char(0),char(85),char(0),char(6),char(0),char(17),char(0),char(13),char(1),
|
char(8),char(0),char(-9),char(0),char(80),char(0),char(4),char(0),char(7),char(0),char(-8),char(0),char(7),char(0),char(-7),char(0),char(7),char(0),char(-6),char(0),
|
||||||
char(13),char(0),char(11),char(1),char(13),char(0),char(14),char(1),char(60),char(0),char(15),char(1),char(4),char(0),char(16),char(1),char(7),char(0),char(12),char(1),
|
char(4),char(0),char(79),char(0),char(81),char(0),char(10),char(0),char(80),char(0),char(-5),char(0),char(13),char(0),char(-4),char(0),char(13),char(0),char(-3),char(0),
|
||||||
char(86),char(0),char(26),char(0),char(4),char(0),char(17),char(1),char(7),char(0),char(18),char(1),char(7),char(0),char(127),char(0),char(7),char(0),char(19),char(1),
|
char(13),char(0),char(-2),char(0),char(13),char(0),char(-1),char(0),char(13),char(0),char(0),char(1),char(7),char(0),char(-99),char(0),char(7),char(0),char(1),char(1),
|
||||||
char(7),char(0),char(20),char(1),char(7),char(0),char(21),char(1),char(7),char(0),char(22),char(1),char(7),char(0),char(23),char(1),char(7),char(0),char(24),char(1),
|
char(4),char(0),char(2),char(1),char(4),char(0),char(53),char(0),char(82),char(0),char(4),char(0),char(80),char(0),char(-5),char(0),char(4),char(0),char(3),char(1),
|
||||||
char(7),char(0),char(25),char(1),char(7),char(0),char(26),char(1),char(7),char(0),char(27),char(1),char(7),char(0),char(28),char(1),char(7),char(0),char(29),char(1),
|
char(7),char(0),char(4),char(1),char(4),char(0),char(5),char(1),char(83),char(0),char(4),char(0),char(13),char(0),char(0),char(1),char(80),char(0),char(-5),char(0),
|
||||||
char(7),char(0),char(30),char(1),char(7),char(0),char(31),char(1),char(7),char(0),char(32),char(1),char(7),char(0),char(33),char(1),char(7),char(0),char(34),char(1),
|
char(4),char(0),char(6),char(1),char(7),char(0),char(7),char(1),char(84),char(0),char(7),char(0),char(13),char(0),char(8),char(1),char(80),char(0),char(-5),char(0),
|
||||||
char(7),char(0),char(35),char(1),char(7),char(0),char(36),char(1),char(4),char(0),char(37),char(1),char(4),char(0),char(38),char(1),char(4),char(0),char(39),char(1),
|
char(4),char(0),char(9),char(1),char(7),char(0),char(10),char(1),char(7),char(0),char(11),char(1),char(7),char(0),char(12),char(1),char(4),char(0),char(53),char(0),
|
||||||
char(4),char(0),char(40),char(1),char(4),char(0),char(120),char(0),char(87),char(0),char(12),char(0),char(17),char(0),char(41),char(1),char(17),char(0),char(42),char(1),
|
char(85),char(0),char(6),char(0),char(17),char(0),char(13),char(1),char(13),char(0),char(11),char(1),char(13),char(0),char(14),char(1),char(60),char(0),char(15),char(1),
|
||||||
char(17),char(0),char(43),char(1),char(13),char(0),char(44),char(1),char(13),char(0),char(45),char(1),char(7),char(0),char(46),char(1),char(4),char(0),char(47),char(1),
|
char(4),char(0),char(16),char(1),char(7),char(0),char(12),char(1),char(86),char(0),char(26),char(0),char(4),char(0),char(17),char(1),char(7),char(0),char(18),char(1),
|
||||||
char(4),char(0),char(48),char(1),char(4),char(0),char(49),char(1),char(4),char(0),char(50),char(1),char(7),char(0),char(10),char(1),char(4),char(0),char(53),char(0),
|
char(7),char(0),char(127),char(0),char(7),char(0),char(19),char(1),char(7),char(0),char(20),char(1),char(7),char(0),char(21),char(1),char(7),char(0),char(22),char(1),
|
||||||
char(88),char(0),char(27),char(0),char(19),char(0),char(51),char(1),char(17),char(0),char(52),char(1),char(17),char(0),char(53),char(1),char(13),char(0),char(44),char(1),
|
char(7),char(0),char(23),char(1),char(7),char(0),char(24),char(1),char(7),char(0),char(25),char(1),char(7),char(0),char(26),char(1),char(7),char(0),char(27),char(1),
|
||||||
char(13),char(0),char(54),char(1),char(13),char(0),char(55),char(1),char(13),char(0),char(56),char(1),char(13),char(0),char(57),char(1),char(13),char(0),char(58),char(1),
|
char(7),char(0),char(28),char(1),char(7),char(0),char(29),char(1),char(7),char(0),char(30),char(1),char(7),char(0),char(31),char(1),char(7),char(0),char(32),char(1),
|
||||||
char(4),char(0),char(59),char(1),char(7),char(0),char(60),char(1),char(4),char(0),char(61),char(1),char(4),char(0),char(62),char(1),char(4),char(0),char(63),char(1),
|
char(7),char(0),char(33),char(1),char(7),char(0),char(34),char(1),char(7),char(0),char(35),char(1),char(7),char(0),char(36),char(1),char(4),char(0),char(37),char(1),
|
||||||
char(7),char(0),char(64),char(1),char(7),char(0),char(65),char(1),char(4),char(0),char(66),char(1),char(4),char(0),char(67),char(1),char(7),char(0),char(68),char(1),
|
char(4),char(0),char(38),char(1),char(4),char(0),char(39),char(1),char(4),char(0),char(40),char(1),char(4),char(0),char(120),char(0),char(87),char(0),char(12),char(0),
|
||||||
char(7),char(0),char(69),char(1),char(7),char(0),char(70),char(1),char(7),char(0),char(71),char(1),char(7),char(0),char(72),char(1),char(7),char(0),char(73),char(1),
|
char(17),char(0),char(41),char(1),char(17),char(0),char(42),char(1),char(17),char(0),char(43),char(1),char(13),char(0),char(44),char(1),char(13),char(0),char(45),char(1),
|
||||||
char(4),char(0),char(74),char(1),char(4),char(0),char(75),char(1),char(4),char(0),char(76),char(1),char(89),char(0),char(12),char(0),char(9),char(0),char(77),char(1),
|
char(7),char(0),char(46),char(1),char(4),char(0),char(47),char(1),char(4),char(0),char(48),char(1),char(4),char(0),char(49),char(1),char(4),char(0),char(50),char(1),
|
||||||
char(9),char(0),char(78),char(1),char(13),char(0),char(79),char(1),char(7),char(0),char(80),char(1),char(7),char(0),char(-125),char(0),char(7),char(0),char(81),char(1),
|
char(7),char(0),char(10),char(1),char(4),char(0),char(53),char(0),char(88),char(0),char(27),char(0),char(19),char(0),char(51),char(1),char(17),char(0),char(52),char(1),
|
||||||
char(4),char(0),char(82),char(1),char(13),char(0),char(83),char(1),char(4),char(0),char(84),char(1),char(4),char(0),char(85),char(1),char(4),char(0),char(86),char(1),
|
char(17),char(0),char(53),char(1),char(13),char(0),char(44),char(1),char(13),char(0),char(54),char(1),char(13),char(0),char(55),char(1),char(13),char(0),char(56),char(1),
|
||||||
char(4),char(0),char(53),char(0),char(90),char(0),char(19),char(0),char(50),char(0),char(-109),char(0),char(87),char(0),char(87),char(1),char(80),char(0),char(88),char(1),
|
char(13),char(0),char(57),char(1),char(13),char(0),char(58),char(1),char(4),char(0),char(59),char(1),char(7),char(0),char(60),char(1),char(4),char(0),char(61),char(1),
|
||||||
char(81),char(0),char(89),char(1),char(82),char(0),char(90),char(1),char(83),char(0),char(91),char(1),char(84),char(0),char(92),char(1),char(85),char(0),char(93),char(1),
|
char(4),char(0),char(62),char(1),char(4),char(0),char(63),char(1),char(7),char(0),char(64),char(1),char(7),char(0),char(65),char(1),char(4),char(0),char(66),char(1),
|
||||||
char(88),char(0),char(94),char(1),char(89),char(0),char(95),char(1),char(4),char(0),char(96),char(1),char(4),char(0),char(62),char(1),char(4),char(0),char(97),char(1),
|
char(4),char(0),char(67),char(1),char(7),char(0),char(68),char(1),char(7),char(0),char(69),char(1),char(7),char(0),char(70),char(1),char(7),char(0),char(71),char(1),
|
||||||
char(4),char(0),char(98),char(1),char(4),char(0),char(99),char(1),char(4),char(0),char(100),char(1),char(4),char(0),char(101),char(1),char(4),char(0),char(102),char(1),
|
char(7),char(0),char(72),char(1),char(7),char(0),char(73),char(1),char(4),char(0),char(74),char(1),char(4),char(0),char(75),char(1),char(4),char(0),char(76),char(1),
|
||||||
char(86),char(0),char(103),char(1),char(91),char(0),char(24),char(0),char(16),char(0),char(104),char(1),char(14),char(0),char(105),char(1),char(14),char(0),char(106),char(1),
|
char(89),char(0),char(12),char(0),char(9),char(0),char(77),char(1),char(9),char(0),char(78),char(1),char(13),char(0),char(79),char(1),char(7),char(0),char(80),char(1),
|
||||||
char(14),char(0),char(107),char(1),char(14),char(0),char(108),char(1),char(14),char(0),char(109),char(1),char(8),char(0),char(110),char(1),char(4),char(0),char(111),char(1),
|
char(7),char(0),char(-125),char(0),char(7),char(0),char(81),char(1),char(4),char(0),char(82),char(1),char(13),char(0),char(83),char(1),char(4),char(0),char(84),char(1),
|
||||||
char(4),char(0),char(86),char(1),char(4),char(0),char(112),char(1),char(4),char(0),char(113),char(1),char(8),char(0),char(114),char(1),char(8),char(0),char(115),char(1),
|
char(4),char(0),char(85),char(1),char(4),char(0),char(86),char(1),char(4),char(0),char(53),char(0),char(90),char(0),char(19),char(0),char(50),char(0),char(-109),char(0),
|
||||||
char(8),char(0),char(116),char(1),char(8),char(0),char(117),char(1),char(8),char(0),char(118),char(1),char(8),char(0),char(119),char(1),char(8),char(0),char(120),char(1),
|
char(87),char(0),char(87),char(1),char(80),char(0),char(88),char(1),char(81),char(0),char(89),char(1),char(82),char(0),char(90),char(1),char(83),char(0),char(91),char(1),
|
||||||
char(8),char(0),char(121),char(1),char(8),char(0),char(122),char(1),char(0),char(0),char(123),char(1),char(0),char(0),char(124),char(1),char(49),char(0),char(125),char(1),
|
char(84),char(0),char(92),char(1),char(85),char(0),char(93),char(1),char(88),char(0),char(94),char(1),char(89),char(0),char(95),char(1),char(4),char(0),char(96),char(1),
|
||||||
char(0),char(0),char(126),char(1),char(92),char(0),char(24),char(0),char(15),char(0),char(104),char(1),char(13),char(0),char(105),char(1),char(13),char(0),char(106),char(1),
|
char(4),char(0),char(62),char(1),char(4),char(0),char(97),char(1),char(4),char(0),char(98),char(1),char(4),char(0),char(99),char(1),char(4),char(0),char(100),char(1),
|
||||||
char(13),char(0),char(107),char(1),char(13),char(0),char(108),char(1),char(13),char(0),char(109),char(1),char(4),char(0),char(112),char(1),char(7),char(0),char(110),char(1),
|
char(4),char(0),char(101),char(1),char(4),char(0),char(102),char(1),char(86),char(0),char(103),char(1),char(91),char(0),char(24),char(0),char(16),char(0),char(104),char(1),
|
||||||
char(4),char(0),char(111),char(1),char(4),char(0),char(86),char(1),char(7),char(0),char(114),char(1),char(7),char(0),char(115),char(1),char(7),char(0),char(116),char(1),
|
char(14),char(0),char(105),char(1),char(14),char(0),char(106),char(1),char(14),char(0),char(107),char(1),char(14),char(0),char(108),char(1),char(14),char(0),char(109),char(1),
|
||||||
char(4),char(0),char(113),char(1),char(7),char(0),char(117),char(1),char(7),char(0),char(118),char(1),char(7),char(0),char(119),char(1),char(7),char(0),char(120),char(1),
|
char(8),char(0),char(110),char(1),char(4),char(0),char(111),char(1),char(4),char(0),char(86),char(1),char(4),char(0),char(112),char(1),char(4),char(0),char(113),char(1),
|
||||||
char(7),char(0),char(121),char(1),char(7),char(0),char(122),char(1),char(0),char(0),char(123),char(1),char(0),char(0),char(124),char(1),char(50),char(0),char(125),char(1),
|
char(8),char(0),char(114),char(1),char(8),char(0),char(115),char(1),char(8),char(0),char(116),char(1),char(8),char(0),char(117),char(1),char(8),char(0),char(118),char(1),
|
||||||
char(0),char(0),char(126),char(1),char(93),char(0),char(9),char(0),char(20),char(0),char(127),char(1),char(14),char(0),char(-128),char(1),char(8),char(0),char(-127),char(1),
|
char(8),char(0),char(119),char(1),char(8),char(0),char(120),char(1),char(8),char(0),char(121),char(1),char(8),char(0),char(122),char(1),char(0),char(0),char(123),char(1),
|
||||||
char(0),char(0),char(-126),char(1),char(91),char(0),char(90),char(1),char(49),char(0),char(-125),char(1),char(0),char(0),char(126),char(1),char(4),char(0),char(97),char(1),
|
char(0),char(0),char(124),char(1),char(49),char(0),char(125),char(1),char(0),char(0),char(126),char(1),char(92),char(0),char(24),char(0),char(15),char(0),char(104),char(1),
|
||||||
char(0),char(0),char(37),char(0),char(94),char(0),char(7),char(0),char(0),char(0),char(-126),char(1),char(92),char(0),char(90),char(1),char(50),char(0),char(-125),char(1),
|
char(13),char(0),char(105),char(1),char(13),char(0),char(106),char(1),char(13),char(0),char(107),char(1),char(13),char(0),char(108),char(1),char(13),char(0),char(109),char(1),
|
||||||
char(19),char(0),char(127),char(1),char(13),char(0),char(-128),char(1),char(7),char(0),char(-127),char(1),char(4),char(0),char(97),char(1),};
|
char(4),char(0),char(112),char(1),char(7),char(0),char(110),char(1),char(4),char(0),char(111),char(1),char(4),char(0),char(86),char(1),char(7),char(0),char(114),char(1),
|
||||||
|
char(7),char(0),char(115),char(1),char(7),char(0),char(116),char(1),char(4),char(0),char(113),char(1),char(7),char(0),char(117),char(1),char(7),char(0),char(118),char(1),
|
||||||
|
char(7),char(0),char(119),char(1),char(7),char(0),char(120),char(1),char(7),char(0),char(121),char(1),char(7),char(0),char(122),char(1),char(0),char(0),char(123),char(1),
|
||||||
|
char(0),char(0),char(124),char(1),char(50),char(0),char(125),char(1),char(0),char(0),char(126),char(1),char(93),char(0),char(9),char(0),char(20),char(0),char(127),char(1),
|
||||||
|
char(14),char(0),char(-128),char(1),char(8),char(0),char(-127),char(1),char(0),char(0),char(-126),char(1),char(91),char(0),char(90),char(1),char(49),char(0),char(-125),char(1),
|
||||||
|
char(0),char(0),char(126),char(1),char(4),char(0),char(97),char(1),char(0),char(0),char(37),char(0),char(94),char(0),char(7),char(0),char(0),char(0),char(-126),char(1),
|
||||||
|
char(92),char(0),char(90),char(1),char(50),char(0),char(-125),char(1),char(19),char(0),char(127),char(1),char(13),char(0),char(-128),char(1),char(7),char(0),char(-127),char(1),
|
||||||
|
char(4),char(0),char(97),char(1),char(95),char(0),char(4),char(0),char(50),char(0),char(-124),char(1),char(9),char(0),char(-123),char(1),char(4),char(0),char(-122),char(1),
|
||||||
|
char(0),char(0),char(37),char(0),char(96),char(0),char(4),char(0),char(49),char(0),char(-124),char(1),char(9),char(0),char(-123),char(1),char(4),char(0),char(-122),char(1),
|
||||||
|
char(0),char(0),char(37),char(0),};
|
||||||
int sBulletDNAlen= sizeof(sBulletDNAstr);
|
int sBulletDNAlen= sizeof(sBulletDNAstr);
|
||||||
|
|||||||
@@ -115,6 +115,7 @@ public:
|
|||||||
|
|
||||||
|
|
||||||
#define BT_MULTIBODY_CODE BT_MAKE_ID('M','B','D','Y')
|
#define BT_MULTIBODY_CODE BT_MAKE_ID('M','B','D','Y')
|
||||||
|
#define BT_MB_LINKCOLLIDER_CODE BT_MAKE_ID('M','B','L','C')
|
||||||
#define BT_SOFTBODY_CODE BT_MAKE_ID('S','B','D','Y')
|
#define BT_SOFTBODY_CODE BT_MAKE_ID('S','B','D','Y')
|
||||||
#define BT_COLLISIONOBJECT_CODE BT_MAKE_ID('C','O','B','J')
|
#define BT_COLLISIONOBJECT_CODE BT_MAKE_ID('C','O','B','J')
|
||||||
#define BT_RIGIDBODY_CODE BT_MAKE_ID('R','B','D','Y')
|
#define BT_RIGIDBODY_CODE BT_MAKE_ID('R','B','D','Y')
|
||||||
@@ -505,7 +506,7 @@ public:
|
|||||||
|
|
||||||
buffer[9] = '2';
|
buffer[9] = '2';
|
||||||
buffer[10] = '8';
|
buffer[10] = '8';
|
||||||
buffer[11] = '7';
|
buffer[11] = '8';
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -1,5 +1,5 @@
|
|||||||
char sBulletDNAstr64[]= {
|
char sBulletDNAstr64[]= {
|
||||||
char(83),char(68),char(78),char(65),char(78),char(65),char(77),char(69),char(-124),char(1),char(0),char(0),char(109),char(95),char(115),char(105),char(122),char(101),char(0),char(109),
|
char(83),char(68),char(78),char(65),char(78),char(65),char(77),char(69),char(-121),char(1),char(0),char(0),char(109),char(95),char(115),char(105),char(122),char(101),char(0),char(109),
|
||||||
char(95),char(99),char(97),char(112),char(97),char(99),char(105),char(116),char(121),char(0),char(42),char(109),char(95),char(100),char(97),char(116),char(97),char(0),char(109),char(95),
|
char(95),char(99),char(97),char(112),char(97),char(99),char(105),char(116),char(121),char(0),char(42),char(109),char(95),char(100),char(97),char(116),char(97),char(0),char(109),char(95),
|
||||||
char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(115),char(0),char(109),char(95),char(99),char(111),
|
char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(115),char(0),char(109),char(95),char(99),char(111),
|
||||||
char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(115),char(0),char(109),char(95),char(99),char(111),char(110),
|
char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(115),char(0),char(109),char(95),char(99),char(111),char(110),
|
||||||
@@ -316,284 +316,292 @@ char(110),char(103),char(80),char(116),char(114),char(0),char(109),char(95),char
|
|||||||
char(110),char(115),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(73),char(110),char(101),char(114),char(116),char(105),char(97),
|
char(110),char(115),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(73),char(110),char(101),char(114),char(116),char(105),char(97),
|
||||||
char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(77),char(97),char(115),char(115),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(78),
|
char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(77),char(97),char(115),char(115),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(78),
|
||||||
char(97),char(109),char(101),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(0),
|
char(97),char(109),char(101),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(0),
|
||||||
char(84),char(89),char(80),char(69),char(95),char(0),char(0),char(0),char(99),char(104),char(97),char(114),char(0),char(117),char(99),char(104),char(97),char(114),char(0),char(115),
|
char(109),char(95),char(99),char(111),char(108),char(79),char(98),char(106),char(68),char(97),char(116),char(97),char(0),char(42),char(109),char(95),char(109),char(117),char(108),char(116),
|
||||||
char(104),char(111),char(114),char(116),char(0),char(117),char(115),char(104),char(111),char(114),char(116),char(0),char(105),char(110),char(116),char(0),char(108),char(111),char(110),char(103),
|
char(105),char(66),char(111),char(100),char(121),char(0),char(109),char(95),char(108),char(105),char(110),char(107),char(0),char(0),char(0),char(0),char(84),char(89),char(80),char(69),
|
||||||
char(0),char(117),char(108),char(111),char(110),char(103),char(0),char(102),char(108),char(111),char(97),char(116),char(0),char(100),char(111),char(117),char(98),char(108),char(101),char(0),
|
char(97),char(0),char(0),char(0),char(99),char(104),char(97),char(114),char(0),char(117),char(99),char(104),char(97),char(114),char(0),char(115),char(104),char(111),char(114),char(116),
|
||||||
char(118),char(111),char(105),char(100),char(0),char(80),char(111),char(105),char(110),char(116),char(101),char(114),char(65),char(114),char(114),char(97),char(121),char(0),char(98),char(116),
|
char(0),char(117),char(115),char(104),char(111),char(114),char(116),char(0),char(105),char(110),char(116),char(0),char(108),char(111),char(110),char(103),char(0),char(117),char(108),char(111),
|
||||||
char(80),char(104),char(121),char(115),char(105),char(99),char(115),char(83),char(121),char(115),char(116),char(101),char(109),char(0),char(76),char(105),char(115),char(116),char(66),char(97),
|
char(110),char(103),char(0),char(102),char(108),char(111),char(97),char(116),char(0),char(100),char(111),char(117),char(98),char(108),char(101),char(0),char(118),char(111),char(105),char(100),
|
||||||
char(115),char(101),char(0),char(98),char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),
|
char(0),char(80),char(111),char(105),char(110),char(116),char(101),char(114),char(65),char(114),char(114),char(97),char(121),char(0),char(98),char(116),char(80),char(104),char(121),char(115),
|
||||||
char(97),char(0),char(98),char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),
|
char(105),char(99),char(115),char(83),char(121),char(115),char(116),char(101),char(109),char(0),char(76),char(105),char(115),char(116),char(66),char(97),char(115),char(101),char(0),char(98),
|
||||||
char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105),char(111),char(110),char(70),char(108),char(111),char(97),char(116),char(68),
|
char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105),char(111),char(110),char(68),char(111),char(117),char(98),
|
char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
||||||
char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(70),char(108),
|
char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105),char(111),char(110),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(68),
|
char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105),char(111),char(110),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),
|
||||||
char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),
|
char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(70),char(108),char(111),char(97),char(116),char(68),
|
||||||
char(109),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111),
|
char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(68),char(111),char(117),char(98),char(108),
|
||||||
char(114),char(109),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(66),char(118),char(104),char(83),char(117),
|
char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),char(109),char(70),char(108),char(111),
|
||||||
char(98),char(116),char(114),char(101),char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(79),char(112),char(116),char(105),
|
char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),char(109),char(68),char(111),
|
||||||
char(109),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),
|
char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(66),char(118),char(104),char(83),char(117),char(98),char(116),char(114),char(101),
|
||||||
char(97),char(0),char(98),char(116),char(79),char(112),char(116),char(105),char(109),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),
|
char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(79),char(112),char(116),char(105),char(109),char(105),char(122),char(101),
|
||||||
char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122),
|
char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
||||||
char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),
|
char(79),char(112),char(116),char(105),char(109),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(68),char(111),char(117),char(98),
|
||||||
char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),char(100),char(66),char(118),
|
||||||
char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),
|
char(104),char(78),char(111),char(100),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),
|
||||||
char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(68),
|
char(100),char(66),char(118),char(104),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116),char(97),char(116),char(105),char(99),char(80),char(108),char(97),char(110),char(101),char(83),char(104),char(97),
|
char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),
|
||||||
char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(118),char(101),char(120),char(73),char(110),char(116),char(101),char(114),
|
char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(110),char(97),char(108),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(115),char(105),char(116),
|
char(98),char(116),char(83),char(116),char(97),char(116),char(105),char(99),char(80),char(108),char(97),char(110),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),
|
||||||
char(105),char(111),char(110),char(65),char(110),char(100),char(82),char(97),char(100),char(105),char(117),char(115),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),
|
char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(118),char(101),char(120),char(73),char(110),char(116),char(101),char(114),char(110),char(97),char(108),char(83),
|
||||||
char(83),char(112),char(104),char(101),char(114),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(73),char(110),
|
char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(65),
|
||||||
char(116),char(73),char(110),char(100),char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110),
|
char(110),char(100),char(82),char(97),char(100),char(105),char(117),char(115),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(83),char(112),char(104),char(101),
|
||||||
char(116),char(73),char(110),char(100),char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110),
|
char(114),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(73),char(110),char(116),char(73),char(110),char(100),
|
||||||
char(116),char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110),char(116),char(73),char(110),char(100),
|
||||||
char(67),char(104),char(97),char(114),char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97),
|
char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110),char(116),char(73),char(110),char(100),
|
||||||
char(0),char(98),char(116),char(77),char(101),char(115),char(104),char(80),char(97),char(114),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116),
|
char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(104),char(97),char(114),
|
||||||
char(114),char(105),char(100),char(105),char(110),char(103),char(77),char(101),char(115),char(104),char(73),char(110),char(116),char(101),char(114),char(102),char(97),char(99),char(101),char(68),
|
char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104),
|
char(101),char(115),char(104),char(80),char(97),char(114),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116),char(114),char(105),char(100),char(105),
|
||||||
char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110),
|
char(110),char(103),char(77),char(101),char(115),char(104),char(73),char(110),char(116),char(101),char(114),char(102),char(97),char(99),char(101),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(102),char(111),char(77),char(97),char(112),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(99),char(97),char(108),char(101),char(100),char(84),char(114),
|
char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),
|
||||||
char(105),char(97),char(110),char(103),char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),
|
char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110),char(102),char(111),char(77),char(97),
|
||||||
char(98),char(116),char(67),char(111),char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101),char(67),char(104),char(105),char(108),char(100),
|
char(112),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(99),char(97),char(108),char(101),char(100),char(84),char(114),char(105),char(97),char(110),char(103),
|
||||||
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101),
|
char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),
|
||||||
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(121),char(108),char(105),char(110),char(100),char(101),char(114),char(83),char(104),char(97),char(112),char(101),
|
char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101),char(67),char(104),char(105),char(108),char(100),char(68),char(97),char(116),char(97),
|
||||||
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),
|
char(0),char(98),char(116),char(67),char(111),char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),
|
||||||
char(0),char(98),char(116),char(67),char(97),char(112),char(115),char(117),char(108),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),
|
char(0),char(98),char(116),char(67),char(121),char(108),char(105),char(110),char(100),char(101),char(114),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),
|
||||||
char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98),
|
char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),
|
||||||
char(116),char(71),char(73),char(109),char(112),char(97),char(99),char(116),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),
|
char(97),char(112),char(115),char(117),char(108),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),
|
||||||
char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(118),char(101),char(120),char(72),char(117),char(108),char(108),char(83),char(104),char(97),char(112),char(101),char(68),
|
char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(73),char(109),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),
|
char(112),char(97),char(99),char(116),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
||||||
char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),
|
char(67),char(111),char(110),char(118),char(101),char(120),char(72),char(117),char(108),char(108),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),
|
char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(68),char(111),char(117),
|
||||||
char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111),char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(68),char(111),
|
char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),
|
||||||
char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111),
|
char(98),char(106),char(101),char(99),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),
|
||||||
char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),
|
char(116),char(97),char(99),char(116),char(83),char(111),char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(68),char(111),char(117),char(98),char(108),char(101),
|
||||||
char(68),char(121),char(110),char(97),char(109),char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(68),char(111),char(117),char(98),char(108),char(101),char(68),
|
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111),char(108),char(118),char(101),char(114),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(68),char(121),char(110),char(97),char(109),char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(70),
|
char(73),char(110),char(102),char(111),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(68),char(121),char(110),char(97),
|
||||||
char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),
|
char(109),char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),
|
char(98),char(116),char(68),char(121),char(110),char(97),char(109),char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(70),char(108),char(111),char(97),char(116),
|
||||||
char(121),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(115),char(116),char(114),
|
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(70),char(108),char(111),char(97),
|
||||||
char(97),char(105),char(110),char(116),char(73),char(110),char(102),char(111),char(49),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),char(110),
|
char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(68),char(111),char(117),
|
||||||
char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),
|
char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),
|
||||||
char(121),char(112),char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),
|
char(73),char(110),char(102),char(111),char(49),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),
|
||||||
char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(121),char(112),
|
char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),
|
||||||
char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),
|
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),
|
||||||
char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),
|
char(105),char(100),char(66),char(111),char(100),char(121),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),
|
||||||
char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),
|
char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),
|
||||||
char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),
|
char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),
|
||||||
char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),
|
char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),
|
||||||
char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),
|
char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),
|
||||||
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),
|
char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),
|
||||||
char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),
|
|
||||||
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),
|
|
||||||
char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),
|
|
||||||
char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116),
|
|
||||||
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),
|
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),
|
||||||
char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),
|
char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),
|
||||||
char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),
|
char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),
|
||||||
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),
|
char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),
|
||||||
char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),
|
char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),
|
||||||
char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),
|
char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116),char(67),char(111),char(110),char(115),
|
||||||
char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),
|
char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),
|
char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),
|
||||||
char(105),char(110),char(103),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),
|
char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(67),char(111),char(110),char(115),
|
||||||
char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),
|
char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),
|
||||||
char(114),char(105),char(110),char(103),char(50),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),
|
char(54),char(68),char(111),char(102),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),
|
||||||
char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(50),
|
char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),
|
||||||
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),
|
char(112),char(114),char(105),char(110),char(103),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(50),char(0),char(98),char(116),char(83),char(108),char(105),char(100),char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),
|
char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(67),
|
||||||
char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(108),char(105),char(100),char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),
|
char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),
|
||||||
char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(97),char(114),
|
char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),
|
||||||
char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),
|
char(50),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),
|
||||||
char(98),char(116),char(71),char(101),char(97),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),
|
char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(50),char(67),char(111),char(110),char(115),
|
||||||
char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(77),char(97),char(116),char(101),char(114),
|
char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),
|
||||||
char(105),char(97),char(108),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(78),char(111),char(100),char(101),
|
char(83),char(108),char(105),char(100),char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),
|
||||||
char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(97),char(116),
|
char(0),char(98),char(116),char(83),char(108),char(105),char(100),char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),
|
||||||
char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(70),char(97),char(99),char(101),char(68),char(97),char(116),char(97),char(0),char(83),
|
char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(97),char(114),char(67),char(111),char(110),char(115),
|
||||||
char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(84),char(101),char(116),char(114),char(97),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),
|
char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),
|
||||||
char(116),char(82),char(105),char(103),char(105),char(100),char(65),char(110),char(99),char(104),char(111),char(114),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),
|
char(97),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),
|
||||||
char(116),char(66),char(111),char(100),char(121),char(67),char(111),char(110),char(102),char(105),char(103),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),
|
char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(77),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(68),
|
||||||
char(66),char(111),char(100),char(121),char(80),char(111),char(115),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),
|
char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(78),char(111),char(100),char(101),char(68),char(97),char(116),char(97),
|
||||||
char(121),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66),
|
char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(97),char(116),char(97),char(0),char(83),char(111),
|
||||||
char(111),char(100),char(121),char(74),char(111),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66),
|
char(102),char(116),char(66),char(111),char(100),char(121),char(70),char(97),char(99),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),
|
||||||
char(111),char(100),char(121),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),
|
char(111),char(100),char(121),char(84),char(101),char(116),char(114),char(97),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(82),char(105),char(103),
|
||||||
char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),
|
char(105),char(100),char(65),char(110),char(99),char(104),char(111),char(114),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),
|
||||||
char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(70),char(108),char(111),char(97),char(116),char(68),
|
char(121),char(67),char(111),char(110),char(102),char(105),char(103),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),
|
||||||
char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(68),char(111),char(117),char(98),char(108),
|
char(80),char(111),char(115),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(67),char(108),char(117),
|
||||||
char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(70),char(108),char(111),
|
char(115),char(116),char(101),char(114),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(74),
|
||||||
char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(0),char(84),char(76),char(69),char(78),char(1),char(0),char(1),char(0),char(2),char(0),char(2),char(0),
|
char(111),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(70),
|
||||||
char(4),char(0),char(4),char(0),char(4),char(0),char(4),char(0),char(8),char(0),char(0),char(0),char(16),char(0),char(48),char(0),char(16),char(0),char(16),char(0),
|
char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),
|
||||||
char(32),char(0),char(16),char(0),char(32),char(0),char(48),char(0),char(96),char(0),char(64),char(0),char(-128),char(0),char(20),char(0),char(48),char(0),char(80),char(0),
|
char(76),char(105),char(110),char(107),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),
|
||||||
char(16),char(0),char(96),char(0),char(-112),char(0),char(16),char(0),char(56),char(0),char(56),char(0),char(20),char(0),char(72),char(0),char(4),char(0),char(4),char(0),
|
char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),
|
||||||
char(8),char(0),char(4),char(0),char(56),char(0),char(32),char(0),char(80),char(0),char(72),char(0),char(96),char(0),char(80),char(0),char(32),char(0),char(64),char(0),
|
char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),
|
||||||
char(64),char(0),char(64),char(0),char(16),char(0),char(72),char(0),char(80),char(0),char(-16),char(1),char(24),char(1),char(-104),char(0),char(88),char(0),char(-72),char(0),
|
char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(70),char(108),char(111),char(97),char(116),char(68),char(97),
|
||||||
char(104),char(0),char(0),char(2),char(-64),char(3),char(8),char(0),char(64),char(0),char(64),char(0),char(0),char(0),char(80),char(0),char(96),char(0),char(-112),char(0),
|
char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(67),char(111),
|
||||||
char(-128),char(0),char(104),char(1),char(-24),char(0),char(-104),char(1),char(-120),char(1),char(-32),char(0),char(8),char(1),char(-40),char(1),char(104),char(1),char(-128),char(2),
|
char(108),char(108),char(105),char(100),char(101),char(114),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),
|
||||||
char(-112),char(2),char(-64),char(4),char(-40),char(0),char(120),char(1),char(104),char(0),char(-104),char(0),char(16),char(0),char(104),char(0),char(24),char(0),char(40),char(0),
|
char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(68),
|
||||||
char(104),char(0),char(96),char(0),char(104),char(0),char(-56),char(0),char(104),char(1),char(112),char(0),char(-24),char(1),char(0),char(3),char(-104),char(1),char(-48),char(0),
|
char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(0),char(0),char(84),char(76),char(69),char(78),char(1),char(0),char(1),char(0),
|
||||||
char(112),char(0),char(0),char(0),char(83),char(84),char(82),char(67),char(84),char(0),char(0),char(0),char(10),char(0),char(3),char(0),char(4),char(0),char(0),char(0),
|
char(2),char(0),char(2),char(0),char(4),char(0),char(4),char(0),char(4),char(0),char(4),char(0),char(8),char(0),char(0),char(0),char(16),char(0),char(48),char(0),
|
||||||
char(4),char(0),char(1),char(0),char(9),char(0),char(2),char(0),char(11),char(0),char(3),char(0),char(10),char(0),char(3),char(0),char(10),char(0),char(4),char(0),
|
char(16),char(0),char(16),char(0),char(32),char(0),char(16),char(0),char(32),char(0),char(48),char(0),char(96),char(0),char(64),char(0),char(-128),char(0),char(20),char(0),
|
||||||
char(10),char(0),char(5),char(0),char(12),char(0),char(2),char(0),char(9),char(0),char(6),char(0),char(9),char(0),char(7),char(0),char(13),char(0),char(1),char(0),
|
char(48),char(0),char(80),char(0),char(16),char(0),char(96),char(0),char(-112),char(0),char(16),char(0),char(56),char(0),char(56),char(0),char(20),char(0),char(72),char(0),
|
||||||
char(7),char(0),char(8),char(0),char(14),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(15),char(0),char(1),char(0),char(7),char(0),char(8),char(0),
|
char(4),char(0),char(4),char(0),char(8),char(0),char(4),char(0),char(56),char(0),char(32),char(0),char(80),char(0),char(72),char(0),char(96),char(0),char(80),char(0),
|
||||||
char(16),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(17),char(0),char(1),char(0),char(13),char(0),char(9),char(0),char(18),char(0),char(1),char(0),
|
char(32),char(0),char(64),char(0),char(64),char(0),char(64),char(0),char(16),char(0),char(72),char(0),char(80),char(0),char(-16),char(1),char(24),char(1),char(-104),char(0),
|
||||||
char(14),char(0),char(9),char(0),char(19),char(0),char(2),char(0),char(17),char(0),char(10),char(0),char(13),char(0),char(11),char(0),char(20),char(0),char(2),char(0),
|
char(88),char(0),char(-72),char(0),char(104),char(0),char(0),char(2),char(-64),char(3),char(8),char(0),char(64),char(0),char(64),char(0),char(0),char(0),char(80),char(0),
|
||||||
char(18),char(0),char(10),char(0),char(14),char(0),char(11),char(0),char(21),char(0),char(4),char(0),char(4),char(0),char(12),char(0),char(4),char(0),char(13),char(0),
|
char(96),char(0),char(-112),char(0),char(-128),char(0),char(104),char(1),char(-24),char(0),char(-104),char(1),char(-120),char(1),char(-32),char(0),char(8),char(1),char(-40),char(1),
|
||||||
char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0),char(22),char(0),char(6),char(0),char(13),char(0),char(16),char(0),char(13),char(0),char(17),char(0),
|
char(104),char(1),char(-128),char(2),char(-112),char(2),char(-64),char(4),char(-40),char(0),char(120),char(1),char(104),char(0),char(-104),char(0),char(16),char(0),char(104),char(0),
|
||||||
char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0),char(0),char(0),char(21),char(0),char(23),char(0),char(6),char(0),
|
char(24),char(0),char(40),char(0),char(104),char(0),char(96),char(0),char(104),char(0),char(-56),char(0),char(104),char(1),char(112),char(0),char(-24),char(1),char(0),char(3),
|
||||||
char(14),char(0),char(16),char(0),char(14),char(0),char(17),char(0),char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0),
|
char(-104),char(1),char(-48),char(0),char(112),char(0),char(40),char(1),char(0),char(2),char(0),char(0),char(83),char(84),char(82),char(67),char(86),char(0),char(0),char(0),
|
||||||
char(0),char(0),char(21),char(0),char(24),char(0),char(3),char(0),char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0),char(4),char(0),char(22),char(0),
|
char(10),char(0),char(3),char(0),char(4),char(0),char(0),char(0),char(4),char(0),char(1),char(0),char(9),char(0),char(2),char(0),char(11),char(0),char(3),char(0),
|
||||||
char(25),char(0),char(12),char(0),char(13),char(0),char(23),char(0),char(13),char(0),char(24),char(0),char(13),char(0),char(25),char(0),char(4),char(0),char(26),char(0),
|
char(10),char(0),char(3),char(0),char(10),char(0),char(4),char(0),char(10),char(0),char(5),char(0),char(12),char(0),char(2),char(0),char(9),char(0),char(6),char(0),
|
||||||
char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0),char(4),char(0),char(29),char(0),char(22),char(0),char(30),char(0),char(24),char(0),char(31),char(0),
|
char(9),char(0),char(7),char(0),char(13),char(0),char(1),char(0),char(7),char(0),char(8),char(0),char(14),char(0),char(1),char(0),char(8),char(0),char(8),char(0),
|
||||||
char(21),char(0),char(32),char(0),char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0),char(26),char(0),char(12),char(0),char(14),char(0),char(23),char(0),
|
char(15),char(0),char(1),char(0),char(7),char(0),char(8),char(0),char(16),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(17),char(0),char(1),char(0),
|
||||||
char(14),char(0),char(24),char(0),char(14),char(0),char(25),char(0),char(4),char(0),char(26),char(0),char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0),
|
char(13),char(0),char(9),char(0),char(18),char(0),char(1),char(0),char(14),char(0),char(9),char(0),char(19),char(0),char(2),char(0),char(17),char(0),char(10),char(0),
|
||||||
char(4),char(0),char(29),char(0),char(23),char(0),char(30),char(0),char(24),char(0),char(31),char(0),char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0),
|
char(13),char(0),char(11),char(0),char(20),char(0),char(2),char(0),char(18),char(0),char(10),char(0),char(14),char(0),char(11),char(0),char(21),char(0),char(4),char(0),
|
||||||
char(21),char(0),char(32),char(0),char(27),char(0),char(3),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(36),char(0),char(0),char(0),char(37),char(0),
|
char(4),char(0),char(12),char(0),char(4),char(0),char(13),char(0),char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0),char(22),char(0),char(6),char(0),
|
||||||
char(28),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0),char(13),char(0),char(40),char(0),char(7),char(0),char(41),char(0),
|
char(13),char(0),char(16),char(0),char(13),char(0),char(17),char(0),char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0),
|
||||||
char(0),char(0),char(21),char(0),char(29),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0),char(13),char(0),char(42),char(0),
|
char(0),char(0),char(21),char(0),char(23),char(0),char(6),char(0),char(14),char(0),char(16),char(0),char(14),char(0),char(17),char(0),char(4),char(0),char(18),char(0),
|
||||||
char(7),char(0),char(43),char(0),char(4),char(0),char(44),char(0),char(30),char(0),char(2),char(0),char(13),char(0),char(45),char(0),char(7),char(0),char(46),char(0),
|
char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0),char(0),char(0),char(21),char(0),char(24),char(0),char(3),char(0),char(2),char(0),char(14),char(0),
|
||||||
char(31),char(0),char(4),char(0),char(29),char(0),char(47),char(0),char(30),char(0),char(48),char(0),char(4),char(0),char(49),char(0),char(0),char(0),char(37),char(0),
|
char(2),char(0),char(15),char(0),char(4),char(0),char(22),char(0),char(25),char(0),char(12),char(0),char(13),char(0),char(23),char(0),char(13),char(0),char(24),char(0),
|
||||||
char(32),char(0),char(1),char(0),char(4),char(0),char(50),char(0),char(33),char(0),char(2),char(0),char(2),char(0),char(50),char(0),char(0),char(0),char(51),char(0),
|
char(13),char(0),char(25),char(0),char(4),char(0),char(26),char(0),char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0),char(4),char(0),char(29),char(0),
|
||||||
char(34),char(0),char(2),char(0),char(2),char(0),char(52),char(0),char(0),char(0),char(51),char(0),char(35),char(0),char(2),char(0),char(0),char(0),char(52),char(0),
|
char(22),char(0),char(30),char(0),char(24),char(0),char(31),char(0),char(21),char(0),char(32),char(0),char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0),
|
||||||
char(0),char(0),char(53),char(0),char(36),char(0),char(8),char(0),char(13),char(0),char(54),char(0),char(14),char(0),char(55),char(0),char(32),char(0),char(56),char(0),
|
char(26),char(0),char(12),char(0),char(14),char(0),char(23),char(0),char(14),char(0),char(24),char(0),char(14),char(0),char(25),char(0),char(4),char(0),char(26),char(0),
|
||||||
char(34),char(0),char(57),char(0),char(35),char(0),char(58),char(0),char(33),char(0),char(59),char(0),char(4),char(0),char(60),char(0),char(4),char(0),char(61),char(0),
|
char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0),char(4),char(0),char(29),char(0),char(23),char(0),char(30),char(0),char(24),char(0),char(31),char(0),
|
||||||
char(37),char(0),char(4),char(0),char(36),char(0),char(62),char(0),char(13),char(0),char(63),char(0),char(4),char(0),char(64),char(0),char(0),char(0),char(37),char(0),
|
char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0),char(21),char(0),char(32),char(0),char(27),char(0),char(3),char(0),char(0),char(0),char(35),char(0),
|
||||||
char(38),char(0),char(7),char(0),char(27),char(0),char(38),char(0),char(37),char(0),char(65),char(0),char(25),char(0),char(66),char(0),char(26),char(0),char(67),char(0),
|
char(4),char(0),char(36),char(0),char(0),char(0),char(37),char(0),char(28),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0),
|
||||||
char(39),char(0),char(68),char(0),char(7),char(0),char(43),char(0),char(0),char(0),char(69),char(0),char(40),char(0),char(2),char(0),char(38),char(0),char(70),char(0),
|
char(13),char(0),char(40),char(0),char(7),char(0),char(41),char(0),char(0),char(0),char(21),char(0),char(29),char(0),char(5),char(0),char(27),char(0),char(38),char(0),
|
||||||
char(13),char(0),char(39),char(0),char(41),char(0),char(4),char(0),char(19),char(0),char(71),char(0),char(27),char(0),char(72),char(0),char(4),char(0),char(73),char(0),
|
char(13),char(0),char(39),char(0),char(13),char(0),char(42),char(0),char(7),char(0),char(43),char(0),char(4),char(0),char(44),char(0),char(30),char(0),char(2),char(0),
|
||||||
char(7),char(0),char(74),char(0),char(42),char(0),char(4),char(0),char(27),char(0),char(38),char(0),char(41),char(0),char(75),char(0),char(4),char(0),char(76),char(0),
|
char(13),char(0),char(45),char(0),char(7),char(0),char(46),char(0),char(31),char(0),char(4),char(0),char(29),char(0),char(47),char(0),char(30),char(0),char(48),char(0),
|
||||||
char(7),char(0),char(43),char(0),char(43),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0),
|
char(4),char(0),char(49),char(0),char(0),char(0),char(37),char(0),char(32),char(0),char(1),char(0),char(4),char(0),char(50),char(0),char(33),char(0),char(2),char(0),
|
||||||
char(44),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(78),char(0),char(0),char(0),char(37),char(0),char(45),char(0),char(3),char(0),
|
char(2),char(0),char(50),char(0),char(0),char(0),char(51),char(0),char(34),char(0),char(2),char(0),char(2),char(0),char(52),char(0),char(0),char(0),char(51),char(0),
|
||||||
char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0),char(46),char(0),char(4),char(0),char(4),char(0),char(79),char(0),
|
char(35),char(0),char(2),char(0),char(0),char(0),char(52),char(0),char(0),char(0),char(53),char(0),char(36),char(0),char(8),char(0),char(13),char(0),char(54),char(0),
|
||||||
char(7),char(0),char(80),char(0),char(7),char(0),char(81),char(0),char(7),char(0),char(82),char(0),char(39),char(0),char(14),char(0),char(4),char(0),char(83),char(0),
|
char(14),char(0),char(55),char(0),char(32),char(0),char(56),char(0),char(34),char(0),char(57),char(0),char(35),char(0),char(58),char(0),char(33),char(0),char(59),char(0),
|
||||||
char(4),char(0),char(84),char(0),char(46),char(0),char(85),char(0),char(4),char(0),char(86),char(0),char(7),char(0),char(87),char(0),char(7),char(0),char(88),char(0),
|
char(4),char(0),char(60),char(0),char(4),char(0),char(61),char(0),char(37),char(0),char(4),char(0),char(36),char(0),char(62),char(0),char(13),char(0),char(63),char(0),
|
||||||
char(7),char(0),char(89),char(0),char(7),char(0),char(90),char(0),char(7),char(0),char(91),char(0),char(4),char(0),char(92),char(0),char(4),char(0),char(93),char(0),
|
char(4),char(0),char(64),char(0),char(0),char(0),char(37),char(0),char(38),char(0),char(7),char(0),char(27),char(0),char(38),char(0),char(37),char(0),char(65),char(0),
|
||||||
char(4),char(0),char(94),char(0),char(4),char(0),char(95),char(0),char(0),char(0),char(37),char(0),char(47),char(0),char(5),char(0),char(27),char(0),char(38),char(0),
|
char(25),char(0),char(66),char(0),char(26),char(0),char(67),char(0),char(39),char(0),char(68),char(0),char(7),char(0),char(43),char(0),char(0),char(0),char(69),char(0),
|
||||||
char(37),char(0),char(65),char(0),char(13),char(0),char(39),char(0),char(7),char(0),char(43),char(0),char(4),char(0),char(96),char(0),char(48),char(0),char(5),char(0),
|
char(40),char(0),char(2),char(0),char(38),char(0),char(70),char(0),char(13),char(0),char(39),char(0),char(41),char(0),char(4),char(0),char(19),char(0),char(71),char(0),
|
||||||
char(29),char(0),char(47),char(0),char(13),char(0),char(97),char(0),char(14),char(0),char(98),char(0),char(4),char(0),char(99),char(0),char(0),char(0),char(100),char(0),
|
char(27),char(0),char(72),char(0),char(4),char(0),char(73),char(0),char(7),char(0),char(74),char(0),char(42),char(0),char(4),char(0),char(27),char(0),char(38),char(0),
|
||||||
char(49),char(0),char(27),char(0),char(9),char(0),char(101),char(0),char(9),char(0),char(102),char(0),char(27),char(0),char(103),char(0),char(0),char(0),char(35),char(0),
|
char(41),char(0),char(75),char(0),char(4),char(0),char(76),char(0),char(7),char(0),char(43),char(0),char(43),char(0),char(3),char(0),char(29),char(0),char(47),char(0),
|
||||||
char(20),char(0),char(104),char(0),char(20),char(0),char(105),char(0),char(14),char(0),char(106),char(0),char(14),char(0),char(107),char(0),char(14),char(0),char(108),char(0),
|
char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0),char(44),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(78),char(0),
|
||||||
char(8),char(0),char(109),char(0),char(8),char(0),char(110),char(0),char(8),char(0),char(111),char(0),char(8),char(0),char(112),char(0),char(8),char(0),char(113),char(0),
|
char(0),char(0),char(37),char(0),char(45),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0),
|
||||||
char(8),char(0),char(114),char(0),char(8),char(0),char(115),char(0),char(8),char(0),char(116),char(0),char(8),char(0),char(117),char(0),char(8),char(0),char(118),char(0),
|
char(46),char(0),char(4),char(0),char(4),char(0),char(79),char(0),char(7),char(0),char(80),char(0),char(7),char(0),char(81),char(0),char(7),char(0),char(82),char(0),
|
||||||
|
char(39),char(0),char(14),char(0),char(4),char(0),char(83),char(0),char(4),char(0),char(84),char(0),char(46),char(0),char(85),char(0),char(4),char(0),char(86),char(0),
|
||||||
|
char(7),char(0),char(87),char(0),char(7),char(0),char(88),char(0),char(7),char(0),char(89),char(0),char(7),char(0),char(90),char(0),char(7),char(0),char(91),char(0),
|
||||||
|
char(4),char(0),char(92),char(0),char(4),char(0),char(93),char(0),char(4),char(0),char(94),char(0),char(4),char(0),char(95),char(0),char(0),char(0),char(37),char(0),
|
||||||
|
char(47),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(37),char(0),char(65),char(0),char(13),char(0),char(39),char(0),char(7),char(0),char(43),char(0),
|
||||||
|
char(4),char(0),char(96),char(0),char(48),char(0),char(5),char(0),char(29),char(0),char(47),char(0),char(13),char(0),char(97),char(0),char(14),char(0),char(98),char(0),
|
||||||
|
char(4),char(0),char(99),char(0),char(0),char(0),char(100),char(0),char(49),char(0),char(27),char(0),char(9),char(0),char(101),char(0),char(9),char(0),char(102),char(0),
|
||||||
|
char(27),char(0),char(103),char(0),char(0),char(0),char(35),char(0),char(20),char(0),char(104),char(0),char(20),char(0),char(105),char(0),char(14),char(0),char(106),char(0),
|
||||||
|
char(14),char(0),char(107),char(0),char(14),char(0),char(108),char(0),char(8),char(0),char(109),char(0),char(8),char(0),char(110),char(0),char(8),char(0),char(111),char(0),
|
||||||
|
char(8),char(0),char(112),char(0),char(8),char(0),char(113),char(0),char(8),char(0),char(114),char(0),char(8),char(0),char(115),char(0),char(8),char(0),char(116),char(0),
|
||||||
|
char(8),char(0),char(117),char(0),char(8),char(0),char(118),char(0),char(4),char(0),char(119),char(0),char(4),char(0),char(120),char(0),char(4),char(0),char(121),char(0),
|
||||||
|
char(4),char(0),char(122),char(0),char(4),char(0),char(123),char(0),char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0),char(0),char(0),char(37),char(0),
|
||||||
|
char(50),char(0),char(27),char(0),char(9),char(0),char(101),char(0),char(9),char(0),char(102),char(0),char(27),char(0),char(103),char(0),char(0),char(0),char(35),char(0),
|
||||||
|
char(19),char(0),char(104),char(0),char(19),char(0),char(105),char(0),char(13),char(0),char(106),char(0),char(13),char(0),char(107),char(0),char(13),char(0),char(108),char(0),
|
||||||
|
char(7),char(0),char(109),char(0),char(7),char(0),char(110),char(0),char(7),char(0),char(111),char(0),char(7),char(0),char(112),char(0),char(7),char(0),char(113),char(0),
|
||||||
|
char(7),char(0),char(114),char(0),char(7),char(0),char(115),char(0),char(7),char(0),char(116),char(0),char(7),char(0),char(117),char(0),char(7),char(0),char(118),char(0),
|
||||||
char(4),char(0),char(119),char(0),char(4),char(0),char(120),char(0),char(4),char(0),char(121),char(0),char(4),char(0),char(122),char(0),char(4),char(0),char(123),char(0),
|
char(4),char(0),char(119),char(0),char(4),char(0),char(120),char(0),char(4),char(0),char(121),char(0),char(4),char(0),char(122),char(0),char(4),char(0),char(123),char(0),
|
||||||
char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0),char(0),char(0),char(37),char(0),char(50),char(0),char(27),char(0),char(9),char(0),char(101),char(0),
|
char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0),char(0),char(0),char(37),char(0),char(51),char(0),char(22),char(0),char(8),char(0),char(126),char(0),
|
||||||
char(9),char(0),char(102),char(0),char(27),char(0),char(103),char(0),char(0),char(0),char(35),char(0),char(19),char(0),char(104),char(0),char(19),char(0),char(105),char(0),
|
char(8),char(0),char(127),char(0),char(8),char(0),char(111),char(0),char(8),char(0),char(-128),char(0),char(8),char(0),char(115),char(0),char(8),char(0),char(-127),char(0),
|
||||||
char(13),char(0),char(106),char(0),char(13),char(0),char(107),char(0),char(13),char(0),char(108),char(0),char(7),char(0),char(109),char(0),char(7),char(0),char(110),char(0),
|
char(8),char(0),char(-126),char(0),char(8),char(0),char(-125),char(0),char(8),char(0),char(-124),char(0),char(8),char(0),char(-123),char(0),char(8),char(0),char(-122),char(0),
|
||||||
char(7),char(0),char(111),char(0),char(7),char(0),char(112),char(0),char(7),char(0),char(113),char(0),char(7),char(0),char(114),char(0),char(7),char(0),char(115),char(0),
|
char(8),char(0),char(-121),char(0),char(8),char(0),char(-120),char(0),char(8),char(0),char(-119),char(0),char(8),char(0),char(-118),char(0),char(8),char(0),char(-117),char(0),
|
||||||
char(7),char(0),char(116),char(0),char(7),char(0),char(117),char(0),char(7),char(0),char(118),char(0),char(4),char(0),char(119),char(0),char(4),char(0),char(120),char(0),
|
char(4),char(0),char(-116),char(0),char(4),char(0),char(-115),char(0),char(4),char(0),char(-114),char(0),char(4),char(0),char(-113),char(0),char(4),char(0),char(-112),char(0),
|
||||||
char(4),char(0),char(121),char(0),char(4),char(0),char(122),char(0),char(4),char(0),char(123),char(0),char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0),
|
char(0),char(0),char(37),char(0),char(52),char(0),char(22),char(0),char(7),char(0),char(126),char(0),char(7),char(0),char(127),char(0),char(7),char(0),char(111),char(0),
|
||||||
char(0),char(0),char(37),char(0),char(51),char(0),char(22),char(0),char(8),char(0),char(126),char(0),char(8),char(0),char(127),char(0),char(8),char(0),char(111),char(0),
|
char(7),char(0),char(-128),char(0),char(7),char(0),char(115),char(0),char(7),char(0),char(-127),char(0),char(7),char(0),char(-126),char(0),char(7),char(0),char(-125),char(0),
|
||||||
char(8),char(0),char(-128),char(0),char(8),char(0),char(115),char(0),char(8),char(0),char(-127),char(0),char(8),char(0),char(-126),char(0),char(8),char(0),char(-125),char(0),
|
char(7),char(0),char(-124),char(0),char(7),char(0),char(-123),char(0),char(7),char(0),char(-122),char(0),char(7),char(0),char(-121),char(0),char(7),char(0),char(-120),char(0),
|
||||||
char(8),char(0),char(-124),char(0),char(8),char(0),char(-123),char(0),char(8),char(0),char(-122),char(0),char(8),char(0),char(-121),char(0),char(8),char(0),char(-120),char(0),
|
char(7),char(0),char(-119),char(0),char(7),char(0),char(-118),char(0),char(7),char(0),char(-117),char(0),char(4),char(0),char(-116),char(0),char(4),char(0),char(-115),char(0),
|
||||||
char(8),char(0),char(-119),char(0),char(8),char(0),char(-118),char(0),char(8),char(0),char(-117),char(0),char(4),char(0),char(-116),char(0),char(4),char(0),char(-115),char(0),
|
char(4),char(0),char(-114),char(0),char(4),char(0),char(-113),char(0),char(4),char(0),char(-112),char(0),char(0),char(0),char(37),char(0),char(53),char(0),char(2),char(0),
|
||||||
char(4),char(0),char(-114),char(0),char(4),char(0),char(-113),char(0),char(4),char(0),char(-112),char(0),char(0),char(0),char(37),char(0),char(52),char(0),char(22),char(0),
|
char(51),char(0),char(-111),char(0),char(14),char(0),char(-110),char(0),char(54),char(0),char(2),char(0),char(52),char(0),char(-111),char(0),char(13),char(0),char(-110),char(0),
|
||||||
char(7),char(0),char(126),char(0),char(7),char(0),char(127),char(0),char(7),char(0),char(111),char(0),char(7),char(0),char(-128),char(0),char(7),char(0),char(115),char(0),
|
char(55),char(0),char(21),char(0),char(50),char(0),char(-109),char(0),char(17),char(0),char(-108),char(0),char(13),char(0),char(-107),char(0),char(13),char(0),char(-106),char(0),
|
||||||
char(7),char(0),char(-127),char(0),char(7),char(0),char(-126),char(0),char(7),char(0),char(-125),char(0),char(7),char(0),char(-124),char(0),char(7),char(0),char(-123),char(0),
|
char(13),char(0),char(-105),char(0),char(13),char(0),char(-104),char(0),char(13),char(0),char(-110),char(0),char(13),char(0),char(-103),char(0),char(13),char(0),char(-102),char(0),
|
||||||
char(7),char(0),char(-122),char(0),char(7),char(0),char(-121),char(0),char(7),char(0),char(-120),char(0),char(7),char(0),char(-119),char(0),char(7),char(0),char(-118),char(0),
|
char(13),char(0),char(-101),char(0),char(13),char(0),char(-100),char(0),char(7),char(0),char(-99),char(0),char(7),char(0),char(-98),char(0),char(7),char(0),char(-97),char(0),
|
||||||
char(7),char(0),char(-117),char(0),char(4),char(0),char(-116),char(0),char(4),char(0),char(-115),char(0),char(4),char(0),char(-114),char(0),char(4),char(0),char(-113),char(0),
|
char(7),char(0),char(-96),char(0),char(7),char(0),char(-95),char(0),char(7),char(0),char(-94),char(0),char(7),char(0),char(-93),char(0),char(7),char(0),char(-92),char(0),
|
||||||
char(4),char(0),char(-112),char(0),char(0),char(0),char(37),char(0),char(53),char(0),char(2),char(0),char(51),char(0),char(-111),char(0),char(14),char(0),char(-110),char(0),
|
char(7),char(0),char(-91),char(0),char(4),char(0),char(-90),char(0),char(56),char(0),char(22),char(0),char(49),char(0),char(-109),char(0),char(18),char(0),char(-108),char(0),
|
||||||
char(54),char(0),char(2),char(0),char(52),char(0),char(-111),char(0),char(13),char(0),char(-110),char(0),char(55),char(0),char(21),char(0),char(50),char(0),char(-109),char(0),
|
char(14),char(0),char(-107),char(0),char(14),char(0),char(-106),char(0),char(14),char(0),char(-105),char(0),char(14),char(0),char(-104),char(0),char(14),char(0),char(-110),char(0),
|
||||||
char(17),char(0),char(-108),char(0),char(13),char(0),char(-107),char(0),char(13),char(0),char(-106),char(0),char(13),char(0),char(-105),char(0),char(13),char(0),char(-104),char(0),
|
char(14),char(0),char(-103),char(0),char(14),char(0),char(-102),char(0),char(14),char(0),char(-101),char(0),char(14),char(0),char(-100),char(0),char(8),char(0),char(-99),char(0),
|
||||||
char(13),char(0),char(-110),char(0),char(13),char(0),char(-103),char(0),char(13),char(0),char(-102),char(0),char(13),char(0),char(-101),char(0),char(13),char(0),char(-100),char(0),
|
char(8),char(0),char(-98),char(0),char(8),char(0),char(-97),char(0),char(8),char(0),char(-96),char(0),char(8),char(0),char(-95),char(0),char(8),char(0),char(-94),char(0),
|
||||||
char(7),char(0),char(-99),char(0),char(7),char(0),char(-98),char(0),char(7),char(0),char(-97),char(0),char(7),char(0),char(-96),char(0),char(7),char(0),char(-95),char(0),
|
char(8),char(0),char(-93),char(0),char(8),char(0),char(-92),char(0),char(8),char(0),char(-91),char(0),char(4),char(0),char(-90),char(0),char(0),char(0),char(37),char(0),
|
||||||
char(7),char(0),char(-94),char(0),char(7),char(0),char(-93),char(0),char(7),char(0),char(-92),char(0),char(7),char(0),char(-91),char(0),char(4),char(0),char(-90),char(0),
|
char(57),char(0),char(2),char(0),char(4),char(0),char(-89),char(0),char(4),char(0),char(-88),char(0),char(58),char(0),char(13),char(0),char(55),char(0),char(-87),char(0),
|
||||||
char(56),char(0),char(22),char(0),char(49),char(0),char(-109),char(0),char(18),char(0),char(-108),char(0),char(14),char(0),char(-107),char(0),char(14),char(0),char(-106),char(0),
|
char(55),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),
|
||||||
char(14),char(0),char(-105),char(0),char(14),char(0),char(-104),char(0),char(14),char(0),char(-110),char(0),char(14),char(0),char(-103),char(0),char(14),char(0),char(-102),char(0),
|
char(4),char(0),char(-82),char(0),char(7),char(0),char(-81),char(0),char(7),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),
|
||||||
char(14),char(0),char(-101),char(0),char(14),char(0),char(-100),char(0),char(8),char(0),char(-99),char(0),char(8),char(0),char(-98),char(0),char(8),char(0),char(-97),char(0),
|
char(7),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),char(59),char(0),char(13),char(0),char(60),char(0),char(-87),char(0),char(60),char(0),char(-86),char(0),
|
||||||
char(8),char(0),char(-96),char(0),char(8),char(0),char(-95),char(0),char(8),char(0),char(-94),char(0),char(8),char(0),char(-93),char(0),char(8),char(0),char(-92),char(0),
|
char(0),char(0),char(35),char(0),char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),
|
||||||
char(8),char(0),char(-91),char(0),char(4),char(0),char(-90),char(0),char(0),char(0),char(37),char(0),char(57),char(0),char(2),char(0),char(4),char(0),char(-89),char(0),
|
char(7),char(0),char(-81),char(0),char(7),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),char(7),char(0),char(-77),char(0),
|
||||||
char(4),char(0),char(-88),char(0),char(58),char(0),char(13),char(0),char(55),char(0),char(-87),char(0),char(55),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),
|
char(4),char(0),char(-76),char(0),char(61),char(0),char(14),char(0),char(56),char(0),char(-87),char(0),char(56),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),
|
||||||
char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(7),char(0),char(-81),char(0),
|
char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(8),char(0),char(-81),char(0),
|
||||||
char(7),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),char(7),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),
|
char(8),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),char(8),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),
|
||||||
char(59),char(0),char(13),char(0),char(60),char(0),char(-87),char(0),char(60),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-85),char(0),
|
char(0),char(0),char(-75),char(0),char(62),char(0),char(3),char(0),char(59),char(0),char(-74),char(0),char(13),char(0),char(-73),char(0),char(13),char(0),char(-72),char(0),
|
||||||
char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(7),char(0),char(-81),char(0),char(7),char(0),char(-80),char(0),
|
char(63),char(0),char(3),char(0),char(61),char(0),char(-74),char(0),char(14),char(0),char(-73),char(0),char(14),char(0),char(-72),char(0),char(64),char(0),char(3),char(0),
|
||||||
char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),char(7),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),char(61),char(0),char(14),char(0),
|
char(59),char(0),char(-74),char(0),char(14),char(0),char(-73),char(0),char(14),char(0),char(-72),char(0),char(65),char(0),char(13),char(0),char(59),char(0),char(-74),char(0),
|
||||||
char(56),char(0),char(-87),char(0),char(56),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0),
|
char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),
|
||||||
char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(8),char(0),char(-81),char(0),char(8),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0),
|
char(7),char(0),char(-66),char(0),char(7),char(0),char(-65),char(0),char(7),char(0),char(-64),char(0),char(7),char(0),char(-63),char(0),char(7),char(0),char(-62),char(0),
|
||||||
char(4),char(0),char(-78),char(0),char(8),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),char(0),char(0),char(-75),char(0),char(62),char(0),char(3),char(0),
|
char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),char(66),char(0),char(13),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),
|
||||||
char(59),char(0),char(-74),char(0),char(13),char(0),char(-73),char(0),char(13),char(0),char(-72),char(0),char(63),char(0),char(3),char(0),char(61),char(0),char(-74),char(0),
|
char(19),char(0),char(-70),char(0),char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),char(7),char(0),char(-66),char(0),
|
||||||
char(14),char(0),char(-73),char(0),char(14),char(0),char(-72),char(0),char(64),char(0),char(3),char(0),char(59),char(0),char(-74),char(0),char(14),char(0),char(-73),char(0),
|
char(7),char(0),char(-65),char(0),char(7),char(0),char(-64),char(0),char(7),char(0),char(-63),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),
|
||||||
char(14),char(0),char(-72),char(0),char(65),char(0),char(13),char(0),char(59),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),
|
char(7),char(0),char(-60),char(0),char(67),char(0),char(14),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),
|
||||||
char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),char(7),char(0),char(-66),char(0),char(7),char(0),char(-65),char(0),
|
char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),char(8),char(0),char(-66),char(0),char(8),char(0),char(-65),char(0),
|
||||||
char(7),char(0),char(-64),char(0),char(7),char(0),char(-63),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),
|
char(8),char(0),char(-64),char(0),char(8),char(0),char(-63),char(0),char(8),char(0),char(-62),char(0),char(8),char(0),char(-61),char(0),char(8),char(0),char(-60),char(0),
|
||||||
char(66),char(0),char(13),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(4),char(0),char(-69),char(0),
|
char(0),char(0),char(-59),char(0),char(68),char(0),char(10),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),
|
||||||
char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),char(7),char(0),char(-66),char(0),char(7),char(0),char(-65),char(0),char(7),char(0),char(-64),char(0),
|
char(8),char(0),char(-58),char(0),char(8),char(0),char(-57),char(0),char(8),char(0),char(-56),char(0),char(8),char(0),char(-62),char(0),char(8),char(0),char(-61),char(0),
|
||||||
char(7),char(0),char(-63),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),char(67),char(0),char(14),char(0),
|
char(8),char(0),char(-60),char(0),char(8),char(0),char(127),char(0),char(69),char(0),char(11),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),
|
||||||
char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0),
|
char(19),char(0),char(-70),char(0),char(7),char(0),char(-58),char(0),char(7),char(0),char(-57),char(0),char(7),char(0),char(-56),char(0),char(7),char(0),char(-62),char(0),
|
||||||
char(4),char(0),char(-67),char(0),char(8),char(0),char(-66),char(0),char(8),char(0),char(-65),char(0),char(8),char(0),char(-64),char(0),char(8),char(0),char(-63),char(0),
|
char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),char(7),char(0),char(127),char(0),char(0),char(0),char(21),char(0),char(70),char(0),char(9),char(0),
|
||||||
char(8),char(0),char(-62),char(0),char(8),char(0),char(-61),char(0),char(8),char(0),char(-60),char(0),char(0),char(0),char(-59),char(0),char(68),char(0),char(10),char(0),
|
|
||||||
char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(8),char(0),char(-58),char(0),char(8),char(0),char(-57),char(0),
|
|
||||||
char(8),char(0),char(-56),char(0),char(8),char(0),char(-62),char(0),char(8),char(0),char(-61),char(0),char(8),char(0),char(-60),char(0),char(8),char(0),char(127),char(0),
|
|
||||||
char(69),char(0),char(11),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(7),char(0),char(-58),char(0),
|
|
||||||
char(7),char(0),char(-57),char(0),char(7),char(0),char(-56),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),
|
|
||||||
char(7),char(0),char(127),char(0),char(0),char(0),char(21),char(0),char(70),char(0),char(9),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),
|
|
||||||
char(19),char(0),char(-70),char(0),char(13),char(0),char(-55),char(0),char(13),char(0),char(-54),char(0),char(13),char(0),char(-53),char(0),char(13),char(0),char(-52),char(0),
|
|
||||||
char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(71),char(0),char(9),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),
|
|
||||||
char(20),char(0),char(-70),char(0),char(14),char(0),char(-55),char(0),char(14),char(0),char(-54),char(0),char(14),char(0),char(-53),char(0),char(14),char(0),char(-52),char(0),
|
|
||||||
char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(72),char(0),char(5),char(0),char(70),char(0),char(-49),char(0),char(4),char(0),char(-48),char(0),
|
|
||||||
char(7),char(0),char(-47),char(0),char(7),char(0),char(-46),char(0),char(7),char(0),char(-45),char(0),char(73),char(0),char(5),char(0),char(71),char(0),char(-49),char(0),
|
|
||||||
char(4),char(0),char(-48),char(0),char(8),char(0),char(-47),char(0),char(8),char(0),char(-46),char(0),char(8),char(0),char(-45),char(0),char(74),char(0),char(41),char(0),
|
|
||||||
char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(13),char(0),char(-55),char(0),char(13),char(0),char(-54),char(0),
|
char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(13),char(0),char(-55),char(0),char(13),char(0),char(-54),char(0),
|
||||||
char(13),char(0),char(-44),char(0),char(13),char(0),char(-43),char(0),char(13),char(0),char(-42),char(0),char(13),char(0),char(-41),char(0),char(13),char(0),char(-40),char(0),
|
char(13),char(0),char(-53),char(0),char(13),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(71),char(0),char(9),char(0),
|
||||||
char(13),char(0),char(-39),char(0),char(13),char(0),char(-38),char(0),char(13),char(0),char(-37),char(0),char(13),char(0),char(-36),char(0),char(13),char(0),char(-35),char(0),
|
char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(14),char(0),char(-55),char(0),char(14),char(0),char(-54),char(0),
|
||||||
char(13),char(0),char(-34),char(0),char(0),char(0),char(-33),char(0),char(0),char(0),char(-32),char(0),char(0),char(0),char(-31),char(0),char(0),char(0),char(-30),char(0),
|
char(14),char(0),char(-53),char(0),char(14),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(72),char(0),char(5),char(0),
|
||||||
char(0),char(0),char(-29),char(0),char(0),char(0),char(-59),char(0),char(13),char(0),char(-53),char(0),char(13),char(0),char(-52),char(0),char(13),char(0),char(-28),char(0),
|
char(70),char(0),char(-49),char(0),char(4),char(0),char(-48),char(0),char(7),char(0),char(-47),char(0),char(7),char(0),char(-46),char(0),char(7),char(0),char(-45),char(0),
|
||||||
char(13),char(0),char(-27),char(0),char(13),char(0),char(-26),char(0),char(13),char(0),char(-25),char(0),char(13),char(0),char(-24),char(0),char(13),char(0),char(-23),char(0),
|
char(73),char(0),char(5),char(0),char(71),char(0),char(-49),char(0),char(4),char(0),char(-48),char(0),char(8),char(0),char(-47),char(0),char(8),char(0),char(-46),char(0),
|
||||||
char(13),char(0),char(-22),char(0),char(13),char(0),char(-21),char(0),char(13),char(0),char(-20),char(0),char(13),char(0),char(-19),char(0),char(13),char(0),char(-18),char(0),
|
char(8),char(0),char(-45),char(0),char(74),char(0),char(41),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),
|
||||||
char(0),char(0),char(-17),char(0),char(0),char(0),char(-16),char(0),char(0),char(0),char(-15),char(0),char(0),char(0),char(-14),char(0),char(0),char(0),char(-13),char(0),
|
char(13),char(0),char(-55),char(0),char(13),char(0),char(-54),char(0),char(13),char(0),char(-44),char(0),char(13),char(0),char(-43),char(0),char(13),char(0),char(-42),char(0),
|
||||||
char(4),char(0),char(-12),char(0),char(75),char(0),char(41),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),
|
char(13),char(0),char(-41),char(0),char(13),char(0),char(-40),char(0),char(13),char(0),char(-39),char(0),char(13),char(0),char(-38),char(0),char(13),char(0),char(-37),char(0),
|
||||||
char(14),char(0),char(-55),char(0),char(14),char(0),char(-54),char(0),char(14),char(0),char(-44),char(0),char(14),char(0),char(-43),char(0),char(14),char(0),char(-42),char(0),
|
char(13),char(0),char(-36),char(0),char(13),char(0),char(-35),char(0),char(13),char(0),char(-34),char(0),char(0),char(0),char(-33),char(0),char(0),char(0),char(-32),char(0),
|
||||||
char(14),char(0),char(-41),char(0),char(14),char(0),char(-40),char(0),char(14),char(0),char(-39),char(0),char(14),char(0),char(-38),char(0),char(14),char(0),char(-37),char(0),
|
char(0),char(0),char(-31),char(0),char(0),char(0),char(-30),char(0),char(0),char(0),char(-29),char(0),char(0),char(0),char(-59),char(0),char(13),char(0),char(-53),char(0),
|
||||||
char(14),char(0),char(-36),char(0),char(14),char(0),char(-35),char(0),char(14),char(0),char(-34),char(0),char(0),char(0),char(-33),char(0),char(0),char(0),char(-32),char(0),
|
char(13),char(0),char(-52),char(0),char(13),char(0),char(-28),char(0),char(13),char(0),char(-27),char(0),char(13),char(0),char(-26),char(0),char(13),char(0),char(-25),char(0),
|
||||||
char(0),char(0),char(-31),char(0),char(0),char(0),char(-30),char(0),char(0),char(0),char(-29),char(0),char(0),char(0),char(-59),char(0),char(14),char(0),char(-53),char(0),
|
char(13),char(0),char(-24),char(0),char(13),char(0),char(-23),char(0),char(13),char(0),char(-22),char(0),char(13),char(0),char(-21),char(0),char(13),char(0),char(-20),char(0),
|
||||||
char(14),char(0),char(-52),char(0),char(14),char(0),char(-28),char(0),char(14),char(0),char(-27),char(0),char(14),char(0),char(-26),char(0),char(14),char(0),char(-25),char(0),
|
char(13),char(0),char(-19),char(0),char(13),char(0),char(-18),char(0),char(0),char(0),char(-17),char(0),char(0),char(0),char(-16),char(0),char(0),char(0),char(-15),char(0),
|
||||||
char(14),char(0),char(-24),char(0),char(14),char(0),char(-23),char(0),char(14),char(0),char(-22),char(0),char(14),char(0),char(-21),char(0),char(14),char(0),char(-20),char(0),
|
char(0),char(0),char(-14),char(0),char(0),char(0),char(-13),char(0),char(4),char(0),char(-12),char(0),char(75),char(0),char(41),char(0),char(61),char(0),char(-74),char(0),
|
||||||
char(14),char(0),char(-19),char(0),char(14),char(0),char(-18),char(0),char(0),char(0),char(-17),char(0),char(0),char(0),char(-16),char(0),char(0),char(0),char(-15),char(0),
|
char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(14),char(0),char(-55),char(0),char(14),char(0),char(-54),char(0),char(14),char(0),char(-44),char(0),
|
||||||
char(0),char(0),char(-14),char(0),char(0),char(0),char(-13),char(0),char(4),char(0),char(-12),char(0),char(76),char(0),char(9),char(0),char(59),char(0),char(-74),char(0),
|
char(14),char(0),char(-43),char(0),char(14),char(0),char(-42),char(0),char(14),char(0),char(-41),char(0),char(14),char(0),char(-40),char(0),char(14),char(0),char(-39),char(0),
|
||||||
char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(7),char(0),char(-55),char(0),char(7),char(0),char(-54),char(0),char(7),char(0),char(-53),char(0),
|
char(14),char(0),char(-38),char(0),char(14),char(0),char(-37),char(0),char(14),char(0),char(-36),char(0),char(14),char(0),char(-35),char(0),char(14),char(0),char(-34),char(0),
|
||||||
char(7),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(77),char(0),char(9),char(0),char(61),char(0),char(-74),char(0),
|
char(0),char(0),char(-33),char(0),char(0),char(0),char(-32),char(0),char(0),char(0),char(-31),char(0),char(0),char(0),char(-30),char(0),char(0),char(0),char(-29),char(0),
|
||||||
char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(8),char(0),char(-55),char(0),char(8),char(0),char(-54),char(0),char(8),char(0),char(-53),char(0),
|
char(0),char(0),char(-59),char(0),char(14),char(0),char(-53),char(0),char(14),char(0),char(-52),char(0),char(14),char(0),char(-28),char(0),char(14),char(0),char(-27),char(0),
|
||||||
char(8),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(78),char(0),char(5),char(0),char(58),char(0),char(-74),char(0),
|
char(14),char(0),char(-26),char(0),char(14),char(0),char(-25),char(0),char(14),char(0),char(-24),char(0),char(14),char(0),char(-23),char(0),char(14),char(0),char(-22),char(0),
|
||||||
char(13),char(0),char(-11),char(0),char(13),char(0),char(-10),char(0),char(7),char(0),char(-9),char(0),char(0),char(0),char(37),char(0),char(79),char(0),char(4),char(0),
|
char(14),char(0),char(-21),char(0),char(14),char(0),char(-20),char(0),char(14),char(0),char(-19),char(0),char(14),char(0),char(-18),char(0),char(0),char(0),char(-17),char(0),
|
||||||
char(61),char(0),char(-74),char(0),char(14),char(0),char(-11),char(0),char(14),char(0),char(-10),char(0),char(8),char(0),char(-9),char(0),char(80),char(0),char(4),char(0),
|
char(0),char(0),char(-16),char(0),char(0),char(0),char(-15),char(0),char(0),char(0),char(-14),char(0),char(0),char(0),char(-13),char(0),char(4),char(0),char(-12),char(0),
|
||||||
char(7),char(0),char(-8),char(0),char(7),char(0),char(-7),char(0),char(7),char(0),char(-6),char(0),char(4),char(0),char(79),char(0),char(81),char(0),char(10),char(0),
|
char(76),char(0),char(9),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(7),char(0),char(-55),char(0),
|
||||||
char(80),char(0),char(-5),char(0),char(13),char(0),char(-4),char(0),char(13),char(0),char(-3),char(0),char(13),char(0),char(-2),char(0),char(13),char(0),char(-1),char(0),
|
char(7),char(0),char(-54),char(0),char(7),char(0),char(-53),char(0),char(7),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),
|
||||||
char(13),char(0),char(0),char(1),char(7),char(0),char(-99),char(0),char(7),char(0),char(1),char(1),char(4),char(0),char(2),char(1),char(4),char(0),char(53),char(0),
|
char(77),char(0),char(9),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(8),char(0),char(-55),char(0),
|
||||||
char(82),char(0),char(4),char(0),char(80),char(0),char(-5),char(0),char(4),char(0),char(3),char(1),char(7),char(0),char(4),char(1),char(4),char(0),char(5),char(1),
|
char(8),char(0),char(-54),char(0),char(8),char(0),char(-53),char(0),char(8),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),
|
||||||
char(83),char(0),char(4),char(0),char(13),char(0),char(0),char(1),char(80),char(0),char(-5),char(0),char(4),char(0),char(6),char(1),char(7),char(0),char(7),char(1),
|
char(78),char(0),char(5),char(0),char(58),char(0),char(-74),char(0),char(13),char(0),char(-11),char(0),char(13),char(0),char(-10),char(0),char(7),char(0),char(-9),char(0),
|
||||||
char(84),char(0),char(7),char(0),char(13),char(0),char(8),char(1),char(80),char(0),char(-5),char(0),char(4),char(0),char(9),char(1),char(7),char(0),char(10),char(1),
|
char(0),char(0),char(37),char(0),char(79),char(0),char(4),char(0),char(61),char(0),char(-74),char(0),char(14),char(0),char(-11),char(0),char(14),char(0),char(-10),char(0),
|
||||||
char(7),char(0),char(11),char(1),char(7),char(0),char(12),char(1),char(4),char(0),char(53),char(0),char(85),char(0),char(6),char(0),char(17),char(0),char(13),char(1),
|
char(8),char(0),char(-9),char(0),char(80),char(0),char(4),char(0),char(7),char(0),char(-8),char(0),char(7),char(0),char(-7),char(0),char(7),char(0),char(-6),char(0),
|
||||||
char(13),char(0),char(11),char(1),char(13),char(0),char(14),char(1),char(60),char(0),char(15),char(1),char(4),char(0),char(16),char(1),char(7),char(0),char(12),char(1),
|
char(4),char(0),char(79),char(0),char(81),char(0),char(10),char(0),char(80),char(0),char(-5),char(0),char(13),char(0),char(-4),char(0),char(13),char(0),char(-3),char(0),
|
||||||
char(86),char(0),char(26),char(0),char(4),char(0),char(17),char(1),char(7),char(0),char(18),char(1),char(7),char(0),char(127),char(0),char(7),char(0),char(19),char(1),
|
char(13),char(0),char(-2),char(0),char(13),char(0),char(-1),char(0),char(13),char(0),char(0),char(1),char(7),char(0),char(-99),char(0),char(7),char(0),char(1),char(1),
|
||||||
char(7),char(0),char(20),char(1),char(7),char(0),char(21),char(1),char(7),char(0),char(22),char(1),char(7),char(0),char(23),char(1),char(7),char(0),char(24),char(1),
|
char(4),char(0),char(2),char(1),char(4),char(0),char(53),char(0),char(82),char(0),char(4),char(0),char(80),char(0),char(-5),char(0),char(4),char(0),char(3),char(1),
|
||||||
char(7),char(0),char(25),char(1),char(7),char(0),char(26),char(1),char(7),char(0),char(27),char(1),char(7),char(0),char(28),char(1),char(7),char(0),char(29),char(1),
|
char(7),char(0),char(4),char(1),char(4),char(0),char(5),char(1),char(83),char(0),char(4),char(0),char(13),char(0),char(0),char(1),char(80),char(0),char(-5),char(0),
|
||||||
char(7),char(0),char(30),char(1),char(7),char(0),char(31),char(1),char(7),char(0),char(32),char(1),char(7),char(0),char(33),char(1),char(7),char(0),char(34),char(1),
|
char(4),char(0),char(6),char(1),char(7),char(0),char(7),char(1),char(84),char(0),char(7),char(0),char(13),char(0),char(8),char(1),char(80),char(0),char(-5),char(0),
|
||||||
char(7),char(0),char(35),char(1),char(7),char(0),char(36),char(1),char(4),char(0),char(37),char(1),char(4),char(0),char(38),char(1),char(4),char(0),char(39),char(1),
|
char(4),char(0),char(9),char(1),char(7),char(0),char(10),char(1),char(7),char(0),char(11),char(1),char(7),char(0),char(12),char(1),char(4),char(0),char(53),char(0),
|
||||||
char(4),char(0),char(40),char(1),char(4),char(0),char(120),char(0),char(87),char(0),char(12),char(0),char(17),char(0),char(41),char(1),char(17),char(0),char(42),char(1),
|
char(85),char(0),char(6),char(0),char(17),char(0),char(13),char(1),char(13),char(0),char(11),char(1),char(13),char(0),char(14),char(1),char(60),char(0),char(15),char(1),
|
||||||
char(17),char(0),char(43),char(1),char(13),char(0),char(44),char(1),char(13),char(0),char(45),char(1),char(7),char(0),char(46),char(1),char(4),char(0),char(47),char(1),
|
char(4),char(0),char(16),char(1),char(7),char(0),char(12),char(1),char(86),char(0),char(26),char(0),char(4),char(0),char(17),char(1),char(7),char(0),char(18),char(1),
|
||||||
char(4),char(0),char(48),char(1),char(4),char(0),char(49),char(1),char(4),char(0),char(50),char(1),char(7),char(0),char(10),char(1),char(4),char(0),char(53),char(0),
|
char(7),char(0),char(127),char(0),char(7),char(0),char(19),char(1),char(7),char(0),char(20),char(1),char(7),char(0),char(21),char(1),char(7),char(0),char(22),char(1),
|
||||||
char(88),char(0),char(27),char(0),char(19),char(0),char(51),char(1),char(17),char(0),char(52),char(1),char(17),char(0),char(53),char(1),char(13),char(0),char(44),char(1),
|
char(7),char(0),char(23),char(1),char(7),char(0),char(24),char(1),char(7),char(0),char(25),char(1),char(7),char(0),char(26),char(1),char(7),char(0),char(27),char(1),
|
||||||
char(13),char(0),char(54),char(1),char(13),char(0),char(55),char(1),char(13),char(0),char(56),char(1),char(13),char(0),char(57),char(1),char(13),char(0),char(58),char(1),
|
char(7),char(0),char(28),char(1),char(7),char(0),char(29),char(1),char(7),char(0),char(30),char(1),char(7),char(0),char(31),char(1),char(7),char(0),char(32),char(1),
|
||||||
char(4),char(0),char(59),char(1),char(7),char(0),char(60),char(1),char(4),char(0),char(61),char(1),char(4),char(0),char(62),char(1),char(4),char(0),char(63),char(1),
|
char(7),char(0),char(33),char(1),char(7),char(0),char(34),char(1),char(7),char(0),char(35),char(1),char(7),char(0),char(36),char(1),char(4),char(0),char(37),char(1),
|
||||||
char(7),char(0),char(64),char(1),char(7),char(0),char(65),char(1),char(4),char(0),char(66),char(1),char(4),char(0),char(67),char(1),char(7),char(0),char(68),char(1),
|
char(4),char(0),char(38),char(1),char(4),char(0),char(39),char(1),char(4),char(0),char(40),char(1),char(4),char(0),char(120),char(0),char(87),char(0),char(12),char(0),
|
||||||
char(7),char(0),char(69),char(1),char(7),char(0),char(70),char(1),char(7),char(0),char(71),char(1),char(7),char(0),char(72),char(1),char(7),char(0),char(73),char(1),
|
char(17),char(0),char(41),char(1),char(17),char(0),char(42),char(1),char(17),char(0),char(43),char(1),char(13),char(0),char(44),char(1),char(13),char(0),char(45),char(1),
|
||||||
char(4),char(0),char(74),char(1),char(4),char(0),char(75),char(1),char(4),char(0),char(76),char(1),char(89),char(0),char(12),char(0),char(9),char(0),char(77),char(1),
|
char(7),char(0),char(46),char(1),char(4),char(0),char(47),char(1),char(4),char(0),char(48),char(1),char(4),char(0),char(49),char(1),char(4),char(0),char(50),char(1),
|
||||||
char(9),char(0),char(78),char(1),char(13),char(0),char(79),char(1),char(7),char(0),char(80),char(1),char(7),char(0),char(-125),char(0),char(7),char(0),char(81),char(1),
|
char(7),char(0),char(10),char(1),char(4),char(0),char(53),char(0),char(88),char(0),char(27),char(0),char(19),char(0),char(51),char(1),char(17),char(0),char(52),char(1),
|
||||||
char(4),char(0),char(82),char(1),char(13),char(0),char(83),char(1),char(4),char(0),char(84),char(1),char(4),char(0),char(85),char(1),char(4),char(0),char(86),char(1),
|
char(17),char(0),char(53),char(1),char(13),char(0),char(44),char(1),char(13),char(0),char(54),char(1),char(13),char(0),char(55),char(1),char(13),char(0),char(56),char(1),
|
||||||
char(4),char(0),char(53),char(0),char(90),char(0),char(19),char(0),char(50),char(0),char(-109),char(0),char(87),char(0),char(87),char(1),char(80),char(0),char(88),char(1),
|
char(13),char(0),char(57),char(1),char(13),char(0),char(58),char(1),char(4),char(0),char(59),char(1),char(7),char(0),char(60),char(1),char(4),char(0),char(61),char(1),
|
||||||
char(81),char(0),char(89),char(1),char(82),char(0),char(90),char(1),char(83),char(0),char(91),char(1),char(84),char(0),char(92),char(1),char(85),char(0),char(93),char(1),
|
char(4),char(0),char(62),char(1),char(4),char(0),char(63),char(1),char(7),char(0),char(64),char(1),char(7),char(0),char(65),char(1),char(4),char(0),char(66),char(1),
|
||||||
char(88),char(0),char(94),char(1),char(89),char(0),char(95),char(1),char(4),char(0),char(96),char(1),char(4),char(0),char(62),char(1),char(4),char(0),char(97),char(1),
|
char(4),char(0),char(67),char(1),char(7),char(0),char(68),char(1),char(7),char(0),char(69),char(1),char(7),char(0),char(70),char(1),char(7),char(0),char(71),char(1),
|
||||||
char(4),char(0),char(98),char(1),char(4),char(0),char(99),char(1),char(4),char(0),char(100),char(1),char(4),char(0),char(101),char(1),char(4),char(0),char(102),char(1),
|
char(7),char(0),char(72),char(1),char(7),char(0),char(73),char(1),char(4),char(0),char(74),char(1),char(4),char(0),char(75),char(1),char(4),char(0),char(76),char(1),
|
||||||
char(86),char(0),char(103),char(1),char(91),char(0),char(24),char(0),char(16),char(0),char(104),char(1),char(14),char(0),char(105),char(1),char(14),char(0),char(106),char(1),
|
char(89),char(0),char(12),char(0),char(9),char(0),char(77),char(1),char(9),char(0),char(78),char(1),char(13),char(0),char(79),char(1),char(7),char(0),char(80),char(1),
|
||||||
char(14),char(0),char(107),char(1),char(14),char(0),char(108),char(1),char(14),char(0),char(109),char(1),char(8),char(0),char(110),char(1),char(4),char(0),char(111),char(1),
|
char(7),char(0),char(-125),char(0),char(7),char(0),char(81),char(1),char(4),char(0),char(82),char(1),char(13),char(0),char(83),char(1),char(4),char(0),char(84),char(1),
|
||||||
char(4),char(0),char(86),char(1),char(4),char(0),char(112),char(1),char(4),char(0),char(113),char(1),char(8),char(0),char(114),char(1),char(8),char(0),char(115),char(1),
|
char(4),char(0),char(85),char(1),char(4),char(0),char(86),char(1),char(4),char(0),char(53),char(0),char(90),char(0),char(19),char(0),char(50),char(0),char(-109),char(0),
|
||||||
char(8),char(0),char(116),char(1),char(8),char(0),char(117),char(1),char(8),char(0),char(118),char(1),char(8),char(0),char(119),char(1),char(8),char(0),char(120),char(1),
|
char(87),char(0),char(87),char(1),char(80),char(0),char(88),char(1),char(81),char(0),char(89),char(1),char(82),char(0),char(90),char(1),char(83),char(0),char(91),char(1),
|
||||||
char(8),char(0),char(121),char(1),char(8),char(0),char(122),char(1),char(0),char(0),char(123),char(1),char(0),char(0),char(124),char(1),char(49),char(0),char(125),char(1),
|
char(84),char(0),char(92),char(1),char(85),char(0),char(93),char(1),char(88),char(0),char(94),char(1),char(89),char(0),char(95),char(1),char(4),char(0),char(96),char(1),
|
||||||
char(0),char(0),char(126),char(1),char(92),char(0),char(24),char(0),char(15),char(0),char(104),char(1),char(13),char(0),char(105),char(1),char(13),char(0),char(106),char(1),
|
char(4),char(0),char(62),char(1),char(4),char(0),char(97),char(1),char(4),char(0),char(98),char(1),char(4),char(0),char(99),char(1),char(4),char(0),char(100),char(1),
|
||||||
char(13),char(0),char(107),char(1),char(13),char(0),char(108),char(1),char(13),char(0),char(109),char(1),char(4),char(0),char(112),char(1),char(7),char(0),char(110),char(1),
|
char(4),char(0),char(101),char(1),char(4),char(0),char(102),char(1),char(86),char(0),char(103),char(1),char(91),char(0),char(24),char(0),char(16),char(0),char(104),char(1),
|
||||||
char(4),char(0),char(111),char(1),char(4),char(0),char(86),char(1),char(7),char(0),char(114),char(1),char(7),char(0),char(115),char(1),char(7),char(0),char(116),char(1),
|
char(14),char(0),char(105),char(1),char(14),char(0),char(106),char(1),char(14),char(0),char(107),char(1),char(14),char(0),char(108),char(1),char(14),char(0),char(109),char(1),
|
||||||
char(4),char(0),char(113),char(1),char(7),char(0),char(117),char(1),char(7),char(0),char(118),char(1),char(7),char(0),char(119),char(1),char(7),char(0),char(120),char(1),
|
char(8),char(0),char(110),char(1),char(4),char(0),char(111),char(1),char(4),char(0),char(86),char(1),char(4),char(0),char(112),char(1),char(4),char(0),char(113),char(1),
|
||||||
char(7),char(0),char(121),char(1),char(7),char(0),char(122),char(1),char(0),char(0),char(123),char(1),char(0),char(0),char(124),char(1),char(50),char(0),char(125),char(1),
|
char(8),char(0),char(114),char(1),char(8),char(0),char(115),char(1),char(8),char(0),char(116),char(1),char(8),char(0),char(117),char(1),char(8),char(0),char(118),char(1),
|
||||||
char(0),char(0),char(126),char(1),char(93),char(0),char(9),char(0),char(20),char(0),char(127),char(1),char(14),char(0),char(-128),char(1),char(8),char(0),char(-127),char(1),
|
char(8),char(0),char(119),char(1),char(8),char(0),char(120),char(1),char(8),char(0),char(121),char(1),char(8),char(0),char(122),char(1),char(0),char(0),char(123),char(1),
|
||||||
char(0),char(0),char(-126),char(1),char(91),char(0),char(90),char(1),char(49),char(0),char(-125),char(1),char(0),char(0),char(126),char(1),char(4),char(0),char(97),char(1),
|
char(0),char(0),char(124),char(1),char(49),char(0),char(125),char(1),char(0),char(0),char(126),char(1),char(92),char(0),char(24),char(0),char(15),char(0),char(104),char(1),
|
||||||
char(0),char(0),char(37),char(0),char(94),char(0),char(7),char(0),char(0),char(0),char(-126),char(1),char(92),char(0),char(90),char(1),char(50),char(0),char(-125),char(1),
|
char(13),char(0),char(105),char(1),char(13),char(0),char(106),char(1),char(13),char(0),char(107),char(1),char(13),char(0),char(108),char(1),char(13),char(0),char(109),char(1),
|
||||||
char(19),char(0),char(127),char(1),char(13),char(0),char(-128),char(1),char(7),char(0),char(-127),char(1),char(4),char(0),char(97),char(1),};
|
char(4),char(0),char(112),char(1),char(7),char(0),char(110),char(1),char(4),char(0),char(111),char(1),char(4),char(0),char(86),char(1),char(7),char(0),char(114),char(1),
|
||||||
|
char(7),char(0),char(115),char(1),char(7),char(0),char(116),char(1),char(4),char(0),char(113),char(1),char(7),char(0),char(117),char(1),char(7),char(0),char(118),char(1),
|
||||||
|
char(7),char(0),char(119),char(1),char(7),char(0),char(120),char(1),char(7),char(0),char(121),char(1),char(7),char(0),char(122),char(1),char(0),char(0),char(123),char(1),
|
||||||
|
char(0),char(0),char(124),char(1),char(50),char(0),char(125),char(1),char(0),char(0),char(126),char(1),char(93),char(0),char(9),char(0),char(20),char(0),char(127),char(1),
|
||||||
|
char(14),char(0),char(-128),char(1),char(8),char(0),char(-127),char(1),char(0),char(0),char(-126),char(1),char(91),char(0),char(90),char(1),char(49),char(0),char(-125),char(1),
|
||||||
|
char(0),char(0),char(126),char(1),char(4),char(0),char(97),char(1),char(0),char(0),char(37),char(0),char(94),char(0),char(7),char(0),char(0),char(0),char(-126),char(1),
|
||||||
|
char(92),char(0),char(90),char(1),char(50),char(0),char(-125),char(1),char(19),char(0),char(127),char(1),char(13),char(0),char(-128),char(1),char(7),char(0),char(-127),char(1),
|
||||||
|
char(4),char(0),char(97),char(1),char(95),char(0),char(4),char(0),char(50),char(0),char(-124),char(1),char(9),char(0),char(-123),char(1),char(4),char(0),char(-122),char(1),
|
||||||
|
char(0),char(0),char(37),char(0),char(96),char(0),char(4),char(0),char(49),char(0),char(-124),char(1),char(9),char(0),char(-123),char(1),char(4),char(0),char(-122),char(1),
|
||||||
|
char(0),char(0),char(37),char(0),};
|
||||||
int sBulletDNAlen64= sizeof(sBulletDNAstr64);
|
int sBulletDNAlen64= sizeof(sBulletDNAstr64);
|
||||||
|
|||||||
@@ -15,7 +15,7 @@
|
|||||||
|
|
||||||
typedef HMODULE CLEW_DYNLIB_HANDLE;
|
typedef HMODULE CLEW_DYNLIB_HANDLE;
|
||||||
|
|
||||||
#define CLEW_DYNLIB_OPEN LoadLibrary
|
#define CLEW_DYNLIB_OPEN LoadLibraryA
|
||||||
#define CLEW_DYNLIB_CLOSE FreeLibrary
|
#define CLEW_DYNLIB_CLOSE FreeLibrary
|
||||||
#define CLEW_DYNLIB_IMPORT GetProcAddress
|
#define CLEW_DYNLIB_IMPORT GetProcAddress
|
||||||
#else
|
#else
|
||||||
|
|||||||
Reference in New Issue
Block a user