Skip to content
Snippets Groups Projects
Commit a5ea51c6 authored by Rainer Kartmann's avatar Rainer Kartmann
Browse files

Merge branch 'fix/bullet-shape-with-cylinder-primitive-half-extent' into 'master'

Fix: Fix using height as half extent for bullet collision shape from primitive cylinder

See merge request !152
parents 50879bb9 0bf6d7e4
No related branches found
No related tags found
1 merge request!152Fix: Fix using height as half extent for bullet collision shape from primitive cylinder
Pipeline #15174 passed
#include "BulletObject.h"
#include "BulletEngine.h"
#include "../../DynamicsWorld.h"
#include <VirtualRobot/VirtualRobot.h>
#include <VirtualRobot/SceneObject.h>
#include <VirtualRobot/Obstacle.h>
#include <Eigen/Dense>
#include <SimoxUtility/math/pose/pose.h>
#include <VirtualRobot/CollisionDetection/CollisionModel.h>
#include <VirtualRobot/Obstacle.h>
#include <VirtualRobot/Primitive.h>
#include <VirtualRobot/SceneObject.h>
#include <VirtualRobot/VirtualRobot.h>
#include <VirtualRobot/Visualization/TriMeshModel.h>
#include <VirtualRobot/Visualization/VisualizationNode.h>
#include <VirtualRobot/Primitive.h>
#include <BulletCollision/CollisionShapes/btShapeHull.h>
#include "../../DynamicsWorld.h"
#include "BulletEngine.h"
#include <BulletCollision/CollisionShapes/btBoxShape.h>
#include <BulletCollision/CollisionShapes/btSphereShape.h>
#include <BulletCollision/CollisionShapes/btCylinderShape.h>
#include <BulletCollision/CollisionShapes/btCompoundShape.h>
#include <Eigen/Dense>
#include <BulletCollision/CollisionShapes/btCylinderShape.h>
#include <BulletCollision/CollisionShapes/btShapeHull.h>
#include <BulletCollision/CollisionShapes/btSphereShape.h>
//#define DEBUG_FIXED_OBJECTS
//#define USE_BULLET_GENERIC_6DOF_CONSTRAINT
......@@ -32,8 +32,7 @@ namespace SimDynamics
float BulletObject::ScaleFactor = 2.0f;
float BulletObject::MassFactor = 0.1f;
BulletObject::BulletObject(VirtualRobot::SceneObjectPtr o)
: DynamicsObject(o)
BulletObject::BulletObject(VirtualRobot::SceneObjectPtr o) : DynamicsObject(o)
{
btScalar interatiaFactor = btScalar(1.0);
#ifdef USE_BULLET_GENERIC_6DOF_CONSTRAINT
......@@ -51,11 +50,13 @@ namespace SimDynamics
}
else
{
THROW_VR_EXCEPTION_IF(!colModel, "No CollisionModel, could not create dynamics model...");
THROW_VR_EXCEPTION_IF(!colModel,
"No CollisionModel, could not create dynamics model...");
if (o->getName() != "Floor")
{
std::vector<Primitive::PrimitivePtr> primitives = colModel->getVisualization()->primitives;
std::vector<Primitive::PrimitivePtr> primitives =
colModel->getVisualization()->primitives;
if (primitives.size() > 0)
{
......@@ -63,40 +64,36 @@ namespace SimDynamics
//o->print();
btCompoundShape* compoundShape = new btCompoundShape(true);
std::vector<Primitive::PrimitivePtr>::const_iterator it;
Eigen::Matrix4f currentTransform = Eigen::Matrix4f::Identity();
Eigen::Matrix4f localComTransform;
localComTransform.setIdentity();
localComTransform.block(0, 3, 3, 1) = -o->getCoMLocal();
//cout << "localComTransform:\n" << localComTransform << std::endl;
currentTransform = localComTransform;
Eigen::Matrix4f currentTransform = Eigen::Matrix4f::Identity();
simox::math::position(currentTransform) = -o->getCoMLocal();
//cout << "currentTransform:\n" << currentTransform << std::endl;
for (it = primitives.begin(); it != primitives.end(); it++)
for (auto it = primitives.begin(); it != primitives.end(); it++)
{
currentTransform *= (*it)->transform;
currentTransform = currentTransform * (*it)->transform;
//currentTransform = localComTransform * (*it)->transform;
//cout << "primitive: (*it)->transform:\n" << (*it)->transform << std::endl;
//cout << "primitive: currentTransform:\n" << currentTransform << std::endl;
compoundShape->addChildShape(BulletEngine::getPoseBullet(currentTransform), getShapeFromPrimitive(*it));
compoundShape->addChildShape(BulletEngine::getPoseBullet(currentTransform),
getShapeFromPrimitive(*it));
}
collisionShape.reset(compoundShape);
// update com
Eigen::Matrix4f comLoc;
comLoc.setIdentity();
comLoc.block(0, 3, 3, 1) = o->getCoMGlobal();
comLoc = (o->getGlobalPose().inverse() * comLoc);
com = comLoc.block(0, 3, 3, 1);
Eigen::Matrix4f comLoc = Eigen::Matrix4f::Identity();
simox::math::position(comLoc) = o->getCoMGlobal();
comLoc = o->getGlobalPose().inverse() * comLoc;
com = simox::math::position(comLoc);
}
else
{
TriMeshModelPtr trimesh;
trimesh = colModel->getTriMeshModel();
THROW_VR_EXCEPTION_IF((!trimesh || trimesh->faces.size() == 0) , "No TriMeshModel, could not create dynamics model...");
THROW_VR_EXCEPTION_IF((!trimesh || trimesh->faces.size() == 0),
"No TriMeshModel, could not create dynamics model...");
collisionShape.reset(createConvexHullShape(trimesh));
}
}
......@@ -104,8 +101,9 @@ namespace SimDynamics
{
// the floor needs a primitive shape, works better with collision handling
VirtualRobot::BoundingBox bb = colModel->getBoundingBox();
Eigen::Vector3f half_size = (bb.getMax() - bb.getMin()) / 1000.0 * ScaleFactor / 2;
btBoxShape* box = new btBoxShape(btVector3(half_size.x(), half_size.y(), half_size.z()));
Eigen::Vector3f half_size = (bb.getMax() - bb.getMin()) / 1000.0 * ScaleFactor / 2;
btBoxShape* box =
new btBoxShape(btVector3(half_size.x(), half_size.y(), half_size.z()));
collisionShape.reset(box);
}
}
......@@ -115,7 +113,8 @@ namespace SimDynamics
btScalar mass = o->getMass();
btVector3 localInertia;
if (mass <= 0 && (o->getSimulationType() == VirtualRobot::SceneObject::Physics::eDynamic || o->getSimulationType() == VirtualRobot::SceneObject::Physics::eUnknown))
if (mass <= 0 && (o->getSimulationType() == VirtualRobot::SceneObject::Physics::eDynamic ||
o->getSimulationType() == VirtualRobot::SceneObject::Physics::eUnknown))
{
//THROW_VR_EXCEPTION ("mass == 0 -> SimulationType must not be eDynamic! ");
mass = btScalar(1.0f); // give object a dummy mass
......@@ -126,7 +125,10 @@ namespace SimDynamics
//type = eKinematic;
if (colModel)
{
VR_WARNING << "Object:" << o->getName() << ": mass == 0 -> SimulationType must not be eDynamic! Setting mass to 1" << std::endl;
VR_WARNING
<< "Object:" << o->getName()
<< ": mass == 0 -> SimulationType must not be eDynamic! Setting mass to 1"
<< std::endl;
}
}
......@@ -136,7 +138,8 @@ namespace SimDynamics
localInertia.setValue(0.0f, 0.0f, 0.0f);
#else
if (o->getSimulationType() != VirtualRobot::SceneObject::Physics::eDynamic && o->getSimulationType() != VirtualRobot::SceneObject::Physics::eUnknown)
if (o->getSimulationType() != VirtualRobot::SceneObject::Physics::eDynamic &&
o->getSimulationType() != VirtualRobot::SceneObject::Physics::eUnknown)
{
mass = 0;
localInertia.setValue(0.0f, 0.0f, 0.0f);
......@@ -149,17 +152,20 @@ namespace SimDynamics
}
else
#ifndef USE_BULLET_GENERIC_6DOF_CONSTRAINT
localInertia.setValue(btScalar(1), btScalar(1), btScalar(1)); // give Object a dummy inertia matrix
localInertia.setValue(
btScalar(1), btScalar(1), btScalar(1)); // give Object a dummy inertia matrix
#else
localInertia.setValue(btScalar(1), btScalar(1), btScalar(1)); // give Object a dummy inertia matrix
localInertia.setValue(
btScalar(1), btScalar(1), btScalar(1)); // give Object a dummy inertia matrix
#endif
}
#endif
localInertia *= interatiaFactor;
motionState = new SimoxMotionState(o);
btRigidBody::btRigidBodyConstructionInfo btRBInfo(mass*MassFactor, motionState, collisionShape.get(), localInertia);
btRigidBody::btRigidBodyConstructionInfo btRBInfo(
mass * MassFactor, motionState, collisionShape.get(), localInertia);
//btRBInfo.m_additionalDamping = true;
rigidBody.reset(new btRigidBody(btRBInfo));
......@@ -174,8 +180,8 @@ namespace SimDynamics
delete motionState;
}
btCollisionShape* BulletObject::getShapeFromPrimitive(VirtualRobot::Primitive::PrimitivePtr primitive)
btCollisionShape*
BulletObject::getShapeFromPrimitive(VirtualRobot::Primitive::PrimitivePtr primitive)
{
btCollisionShape* result;
......@@ -183,19 +189,28 @@ namespace SimDynamics
{
Primitive::Box* box = std::dynamic_pointer_cast<Primitive::Box>(primitive).get();
// w/h/d have to be halved
btBoxShape* boxShape = new btBoxShape(btVector3(box->width / 2000.f * ScaleFactor, box->height / 2000.f * ScaleFactor, box->depth / 2000.f * ScaleFactor));
btBoxShape* boxShape = new btBoxShape(btVector3(box->width / 1000.f * ScaleFactor / 2,
box->height / 1000.f * ScaleFactor / 2,
box->depth / 1000.f * ScaleFactor / 2));
result = boxShape;
}
else if (primitive->type == Primitive::Sphere::TYPE)
{
Primitive::Sphere* sphere = std::dynamic_pointer_cast<Primitive::Sphere>(primitive).get();
btSphereShape* sphereShape = new btSphereShape(btScalar(sphere->radius / 1000.0 * ScaleFactor));
Primitive::Sphere* sphere =
std::dynamic_pointer_cast<Primitive::Sphere>(primitive).get();
btSphereShape* sphereShape =
new btSphereShape(btScalar(sphere->radius / 1000.0 * ScaleFactor));
result = sphereShape;
}
else if (primitive->type == Primitive::Cylinder::TYPE)
{
Primitive::Cylinder* cyl = std::dynamic_pointer_cast<Primitive::Cylinder>(primitive).get();
btCylinderShape* cylShape = new btCylinderShape(btVector3(cyl->radius / 1000.0 * ScaleFactor, cyl->height / 1000.0 * ScaleFactor, cyl->radius / 1000.0 * ScaleFactor));
Primitive::Cylinder* cyl =
std::dynamic_pointer_cast<Primitive::Cylinder>(primitive).get();
// height has to be halved
btCylinderShape* cylShape =
new btCylinderShape(btVector3(cyl->radius / 1000.0 * ScaleFactor,
cyl->height / 1000.0 * ScaleFactor / 2,
cyl->radius / 1000.0 * ScaleFactor));
result = cylShape;
}
else
......@@ -207,7 +222,8 @@ namespace SimDynamics
return result;
}
btCollisionShape* BulletObject::createConvexHullShape(VirtualRobot::TriMeshModelPtr trimesh)
btCollisionShape*
BulletObject::createConvexHullShape(VirtualRobot::TriMeshModelPtr trimesh)
{
VR_ASSERT(trimesh);
// create triangle shape
......@@ -228,14 +244,20 @@ namespace SimDynamics
sc = 0.001f * ScaleFactor;
}
for (auto & face : trimesh->faces)
for (auto& face : trimesh->faces)
{
auto & vertex1 = trimesh->vertices.at(face.id1);
auto & vertex2 = trimesh->vertices.at(face.id2);
auto & vertex3 = trimesh->vertices.at(face.id3);
btVector3 v1(btScalar((vertex1[0] - com[0])*sc), btScalar((vertex1[1] - com[1])*sc), btScalar((vertex1[2] - com[2])*sc));
btVector3 v2(btScalar((vertex2[0] - com[0])*sc), btScalar((vertex2[1] - com[1])*sc), btScalar((vertex2[2] - com[2])*sc));
btVector3 v3(btScalar((vertex3[0] - com[0])*sc), btScalar((vertex3[1] - com[1])*sc), btScalar((vertex3[2] - com[2])*sc));
auto& vertex1 = trimesh->vertices.at(face.id1);
auto& vertex2 = trimesh->vertices.at(face.id2);
auto& vertex3 = trimesh->vertices.at(face.id3);
btVector3 v1(btScalar((vertex1[0] - com[0]) * sc),
btScalar((vertex1[1] - com[1]) * sc),
btScalar((vertex1[2] - com[2]) * sc));
btVector3 v2(btScalar((vertex2[0] - com[0]) * sc),
btScalar((vertex2[1] - com[1]) * sc),
btScalar((vertex2[2] - com[2]) * sc));
btVector3 v3(btScalar((vertex3[0] - com[0]) * sc),
btScalar((vertex3[1] - com[1]) * sc),
btScalar((vertex3[2] - com[2]) * sc));
btTrimesh->addTriangle(v1, v2, v3);
}
......@@ -247,7 +269,6 @@ namespace SimDynamics
com = comConv.block(0,3,3,1);*/
if (sceneObject->getSimulationType() == VirtualRobot::SceneObject::Physics::eKinematic)
{
// Support concave objects if they are not dynamic
......@@ -256,7 +277,8 @@ namespace SimDynamics
else
{
// build convex hull
std::shared_ptr<btConvexShape> btConvexShape(new btConvexTriangleMeshShape(btTrimesh.get()));
std::shared_ptr<btConvexShape> btConvexShape(
new btConvexTriangleMeshShape(btTrimesh.get()));
btConvexShape->setMargin(btMargin);
std::shared_ptr<btShapeHull> btHull(new btShapeHull(btConvexShape.get()));
......@@ -277,12 +299,14 @@ namespace SimDynamics
}
}
std::shared_ptr<btRigidBody> BulletObject::getRigidBody()
std::shared_ptr<btRigidBody>
BulletObject::getRigidBody()
{
return rigidBody;
}
void BulletObject::setPosition(const Eigen::Vector3f& posMM)
void
BulletObject::setPosition(const Eigen::Vector3f& posMM)
{
MutexLockPtr lock = getScopedLock();
Eigen::Matrix4f pose = Eigen::Matrix4f::Identity();
......@@ -290,7 +314,8 @@ namespace SimDynamics
setPose(pose);
}
void BulletObject::setPoseIntern(const Eigen::Matrix4f& pose)
void
BulletObject::setPoseIntern(const Eigen::Matrix4f& pose)
{
MutexLockPtr lock = getScopedLock();
/* convert to local coord system, apply comoffset and convert back*/
......@@ -300,20 +325,22 @@ namespace SimDynamics
this->rigidBody->setWorldTransform(BulletEngine::getPoseBullet(poseGlobal));
// notify motionState of non-robot nodes
if(!std::dynamic_pointer_cast<VirtualRobot::RobotNode>(sceneObject))
if (!std::dynamic_pointer_cast<VirtualRobot::RobotNode>(sceneObject))
{
motionState->setGlobalPose(pose);
}
}
void BulletObject::setPose(const Eigen::Matrix4f& pose)
void
BulletObject::setPose(const Eigen::Matrix4f& pose)
{
MutexLockPtr lock = getScopedLock();
DynamicsObject::setPose(pose);
setPoseIntern(pose);
}
Eigen::Vector3f BulletObject::getLinearVelocity()
Eigen::Vector3f
BulletObject::getLinearVelocity()
{
MutexLockPtr lock = getScopedLock();
......@@ -325,7 +352,8 @@ namespace SimDynamics
return (BulletEngine::getVecEigen(rigidBody->getLinearVelocity()));
}
Eigen::Vector3f BulletObject::getAngularVelocity()
Eigen::Vector3f
BulletObject::getAngularVelocity()
{
MutexLockPtr lock = getScopedLock();
......@@ -337,7 +365,8 @@ namespace SimDynamics
return (BulletEngine::getVecEigen(rigidBody->getAngularVelocity(), false));
}
void BulletObject::setLinearVelocity(const Eigen::Vector3f& vel)
void
BulletObject::setLinearVelocity(const Eigen::Vector3f& vel)
{
MutexLockPtr lock = getScopedLock();
......@@ -351,7 +380,8 @@ namespace SimDynamics
rigidBody->setLinearVelocity(btVel);
}
void BulletObject::setAngularVelocity(const Eigen::Vector3f& vel)
void
BulletObject::setAngularVelocity(const Eigen::Vector3f& vel)
{
MutexLockPtr lock = getScopedLock();
......@@ -365,7 +395,8 @@ namespace SimDynamics
rigidBody->setAngularVelocity(btVel);
}
Eigen::Matrix4f BulletObject::getComGlobal()
Eigen::Matrix4f
BulletObject::getComGlobal()
{
MutexLockPtr lock = getScopedLock();
btTransform tr;
......@@ -373,7 +404,8 @@ namespace SimDynamics
return BulletEngine::getPoseEigen(tr);
}
void BulletObject::applyForce(const Eigen::Vector3f& force)
void
BulletObject::applyForce(const Eigen::Vector3f& force)
{
MutexLockPtr lock = getScopedLock();
......@@ -387,7 +419,8 @@ namespace SimDynamics
rigidBody->applyCentralForce(btVel);
}
void BulletObject::applyTorque(const Eigen::Vector3f& torque)
void
BulletObject::applyTorque(const Eigen::Vector3f& torque)
{
MutexLockPtr lock = getScopedLock();
......@@ -401,7 +434,8 @@ namespace SimDynamics
rigidBody->applyTorque(btVel);
}
void BulletObject::setSimType(VirtualRobot::SceneObject::Physics::SimulationType s)
void
BulletObject::setSimType(VirtualRobot::SceneObject::Physics::SimulationType s)
{
btVector3 localInertia;
localInertia.setZero();
......@@ -430,14 +464,16 @@ namespace SimDynamics
}
else
{
localInertia.setValue(btScalar(1), btScalar(1), btScalar(1)); // give Object a dummy inertia matrix
localInertia.setValue(btScalar(1),
btScalar(1),
btScalar(1)); // give Object a dummy inertia matrix
}
mass = sceneObject->getMass();
btColFlag = 0;
break;
default:
break;
break;
}
rigidBody->setMassProps(mass, localInertia);
......@@ -446,7 +482,8 @@ namespace SimDynamics
DynamicsObject::setSimType(s);
}
void BulletObject::activate()
void
BulletObject::activate()
{
MutexLockPtr lock = getScopedLock();
......@@ -459,4 +496,4 @@ namespace SimDynamics
}
} // namespace VirtualRobot
} // namespace SimDynamics
......@@ -22,10 +22,10 @@
*/
#pragma once
#include "../DynamicsObject.h"
#include "SimoxMotionState.h"
#include <VirtualRobot/Primitive.h>
#include "../DynamicsObject.h"
#include "SimoxMotionState.h"
#include "btBulletDynamicsCommon.h"
namespace SimDynamics
......@@ -58,7 +58,8 @@ namespace SimDynamics
*/
void setPose(const Eigen::Matrix4f& pose) override;
Eigen::Vector3f getCom()
Eigen::Vector3f
getCom()
{
return com;
}
......@@ -97,7 +98,6 @@ namespace SimDynamics
static float MassFactor;
protected:
void setPoseIntern(const Eigen::Matrix4f& pose);
btCollisionShape* getShapeFromPrimitive(VirtualRobot::Primitive::PrimitivePtr primitive);
......@@ -111,10 +111,8 @@ namespace SimDynamics
btScalar btMargin;
SimoxMotionState* motionState;
};
typedef std::shared_ptr<BulletObject> BulletObjectPtr;
} // namespace SimDynamics
This diff is collapsed.
......@@ -24,7 +24,6 @@
#include "../DynamicsRobot.h"
#include "BulletObject.h"
#include "btBulletDynamicsCommon.h"
namespace SimDynamics
......@@ -32,6 +31,7 @@ namespace SimDynamics
class SIMDYNAMICS_IMPORT_EXPORT BulletRobot : public DynamicsRobot
{
friend class BulletEngine;
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
......@@ -53,7 +53,7 @@ namespace SimDynamics
//VirtualRobot::RobotNodePtr nodeJoint2; // joint2 (only used for hinge2/universal joints)
BulletObjectPtr dynNode1; // parent
BulletObjectPtr dynNode2; // child
std::vector< std::pair<DynamicsObjectPtr, DynamicsObjectPtr> > disabledCollisionPairs;
std::vector<std::pair<DynamicsObjectPtr, DynamicsObjectPtr>> disabledCollisionPairs;
std::shared_ptr<btTypedConstraint> joint;
double jointValueOffset; // offset simox -> bullet joint values
};
......@@ -216,9 +216,14 @@ namespace SimDynamics
// fixed (joint=fixed !joint2)
// hinge (joint=revolute !joint2)
// universal (hinge2) (joint=revolute joint2=revolute) // experimental
void createLink(VirtualRobot::RobotNodePtr bodyA, VirtualRobot::RobotNodePtr joint, /*VirtualRobot::RobotNodePtr joint2,*/ VirtualRobot::RobotNodePtr bodyB, bool enableJointMotors);
void createLink(VirtualRobot::RobotNodePtr bodyA,
VirtualRobot::RobotNodePtr joint,
/*VirtualRobot::RobotNodePtr joint2,*/ VirtualRobot::RobotNodePtr bodyB,
bool enableJointMotors);
void createLink(VirtualRobot::RobotNodePtr node1, VirtualRobot::RobotNodePtr node2, bool enableJointMotors);
void createLink(VirtualRobot::RobotNodePtr node1,
VirtualRobot::RobotNodePtr node2,
bool enableJointMotors);
// ensure that all robot nodes, which are not actuated directly, are at the correct pose
void setPoseNonActuatedRobotNodes();
......@@ -232,9 +237,32 @@ namespace SimDynamics
std::vector<LinkInfo> links;
btScalar bulletMaxMotorImulse;
std::shared_ptr<btTypedConstraint> createFixedJoint(std::shared_ptr<btRigidBody> btBody1, std::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2);
std::shared_ptr<btTypedConstraint> createHingeJoint(std::shared_ptr<btRigidBody> btBody1, std::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& coordSystemNode1, Eigen::Matrix4f& coordSystemNode2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2, Eigen::Vector3f& axisGlobal, Eigen::Vector3f& axisLocal, Eigen::Matrix4f& coordSystemJoint, double limMinBT, double limMaxBT);
std::shared_ptr<btTypedConstraint> createTranslationalJoint(std::shared_ptr<btRigidBody> btBody1, std::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& coordSystemNode1, Eigen::Matrix4f& coordSystemNode2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2, Eigen::Vector3f& directionLocal, Eigen::Matrix4f& coordSystemJoint, double limMinBT, double limMaxBT);
std::shared_ptr<btTypedConstraint> createFixedJoint(std::shared_ptr<btRigidBody> btBody1,
std::shared_ptr<btRigidBody> btBody2,
Eigen::Matrix4f& anchor_inNode1,
Eigen::Matrix4f& anchor_inNode2);
std::shared_ptr<btTypedConstraint> createHingeJoint(std::shared_ptr<btRigidBody> btBody1,
std::shared_ptr<btRigidBody> btBody2,
Eigen::Matrix4f& coordSystemNode1,
Eigen::Matrix4f& coordSystemNode2,
Eigen::Matrix4f& anchor_inNode1,
Eigen::Matrix4f& anchor_inNode2,
Eigen::Vector3f& axisGlobal,
Eigen::Vector3f& axisLocal,
Eigen::Matrix4f& coordSystemJoint,
double limMinBT,
double limMaxBT);
std::shared_ptr<btTypedConstraint>
createTranslationalJoint(std::shared_ptr<btRigidBody> btBody1,
std::shared_ptr<btRigidBody> btBody2,
Eigen::Matrix4f& coordSystemNode1,
Eigen::Matrix4f& coordSystemNode2,
Eigen::Matrix4f& anchor_inNode1,
Eigen::Matrix4f& anchor_inNode2,
Eigen::Vector3f& directionLocal,
Eigen::Matrix4f& coordSystemJoint,
double limMinBT,
double limMaxBT);
bool ignoreTranslationalJoints;
......@@ -243,4 +271,3 @@ namespace SimDynamics
typedef std::shared_ptr<BulletRobot> BulletRobotPtr;
} // namespace SimDynamics
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment