Add API to set bunny properties. Add example to show coupling between softbody and multibody.
This commit is contained in:
@@ -408,7 +408,7 @@ public:
|
||||
|
||||
}
|
||||
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
|
||||
m_robotSim.loadBunny();
|
||||
m_robotSim.loadBunny(0.1,0.1,0.02);
|
||||
|
||||
b3JointInfo revoluteJoint1;
|
||||
revoluteJoint1.m_parentFrame[0] = -0.007;
|
||||
@@ -571,6 +571,46 @@ public:
|
||||
m_robotSim.createJoint(0, 2, 0, 4, &revoluteJoint7);
|
||||
m_robotSim.createJoint(0, 3, 0, 5, &revoluteJoint8);
|
||||
}
|
||||
|
||||
if ((m_options & eSOFTBODY_MULTIBODY_COUPLING)!=0)
|
||||
{
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
args.m_fileName = "kuka_iiwa/model_free_base.urdf";
|
||||
args.m_startPosition.setValue(0,1.0,2.0);
|
||||
args.m_startOrientation.setEulerZYX(0,0,1.57);
|
||||
args.m_forceOverrideFixedBase = false;
|
||||
args.m_useMultiBody = true;
|
||||
b3RobotSimLoadFileResults results;
|
||||
m_robotSim.loadFile(args,results);
|
||||
|
||||
int kukaId = results.m_uniqueObjectIds[0];
|
||||
int numJoints = m_robotSim.getNumJoints(kukaId);
|
||||
b3Printf("numJoints = %d",numJoints);
|
||||
|
||||
for (int i=0;i<numJoints;i++)
|
||||
{
|
||||
b3JointInfo jointInfo;
|
||||
m_robotSim.getJointInfo(kukaId,i,&jointInfo);
|
||||
b3Printf("joint[%d].m_jointName=%s",i,jointInfo.m_jointName);
|
||||
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
|
||||
controlArgs.m_maxTorqueValue = 0.0;
|
||||
m_robotSim.setJointMotorControl(kukaId,i,controlArgs);
|
||||
}
|
||||
}
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
args.m_fileName = "plane.urdf";
|
||||
args.m_startPosition.setValue(0,0,0);
|
||||
args.m_startOrientation.setEulerZYX(0,0,0);
|
||||
args.m_forceOverrideFixedBase = true;
|
||||
args.m_useMultiBody = true;
|
||||
b3RobotSimLoadFileResults results;
|
||||
m_robotSim.loadFile(args,results);
|
||||
}
|
||||
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
|
||||
m_robotSim.loadBunny(0.5,10.0,0.1);
|
||||
}
|
||||
}
|
||||
virtual void exitPhysics()
|
||||
{
|
||||
|
||||
Reference in New Issue
Block a user