expose b3PhysicsParamSetNumSolverIterations

split Visual Studio project generation batch file in regular and VR+pybullet+double precision build.
disable KUKA iiwa joint limit hack
This commit is contained in:
erwin coumans
2016-10-05 16:31:48 -07:00
parent d6f449762b
commit d59b0f05a4
6 changed files with 39 additions and 19 deletions

View File

@@ -1,9 +1,5 @@
IF NOT EXIST bin mkdir bin
IF NOT EXIST bin\openvr_api.dll copy examples\ThirdPartyLibs\openvr\bin\win32\openvr_api.dll bin
cd build3 cd build3
premake4 --enable_openvr --targetdir="../bin" vs2010 premake4 --targetdir="../bin" vs2010
start vs2010
rem premake4 --double --enable_pybullet --python_include_dir="C:/Python-3.5.2/include" --python_lib_dir="C:/Python-3.5.2/libs" --enable_openvr --targetdir="../bin" vs2010
pause

View File

@@ -0,0 +1,8 @@
IF NOT EXIST bin mkdir bin
IF NOT EXIST bin\openvr_api.dll copy examples\ThirdPartyLibs\openvr\bin\win32\openvr_api.dll bin
cd build3
premake4 --double --enable_openvr --enable_pybullet --python_include_dir="C:/Python-3.5.2/include" --python_lib_dir="C:/Python-3.5.2/libs" --targetdir="../bin" vs2010
start vs2010

View File

@@ -174,7 +174,7 @@
<child link="lbr_iiwa_link_4"/> <child link="lbr_iiwa_link_4"/>
<origin rpy="1.57079632679 0 0" xyz="0 0 0.2155"/> <origin rpy="1.57079632679 0 0" xyz="0 0 0.2155"/>
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
<limit effort="300" lower=".29439510239" upper="2.09439510239" velocity="10"/> <limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
<dynamics damping="0.5"/> <dynamics damping="0.5"/>
</joint> </joint>
<link name="lbr_iiwa_link_4"> <link name="lbr_iiwa_link_4">

View File

@@ -145,6 +145,15 @@ int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandH
return 0; return 0;
} }
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
command->m_physSimParamArgs.m_numSolverIterations = numSolverIterations;
command->m_updateFlags |= SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS;
return 0;
}
int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep) int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep)
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;

View File

@@ -101,6 +101,9 @@ int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double
int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP); int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP);
int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps); int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps);
int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation); int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation);
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations);
b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient); b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient);

View File

@@ -1490,7 +1490,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break; break;
} }
case CMD_SEND_DESIRED_STATE: case CMD_SEND_DESIRED_STATE:
{ {
if (m_data->m_verboseOutput) if (m_data->m_verboseOutput)
{ {
@@ -1670,18 +1670,18 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break; break;
} }
default: default:
{ {
b3Warning("m_controlMode not implemented yet"); b3Warning("m_controlMode not implemented yet");
break; break;
} }
} }
} }
serverStatusOut.m_type = CMD_DESIRED_STATE_RECEIVED_COMPLETED; serverStatusOut.m_type = CMD_DESIRED_STATE_RECEIVED_COMPLETED;
hasStatus = true; hasStatus = true;
break; break;
} }
case CMD_REQUEST_ACTUAL_STATE: case CMD_REQUEST_ACTUAL_STATE:
{ {
if (m_data->m_verboseOutput) if (m_data->m_verboseOutput)
@@ -1944,6 +1944,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
} }
} }
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS)
{
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = clientCmd.m_physSimParamArgs.m_numSolverIterations;
}
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS) if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS)
{ {
m_data->m_numSimulationSubSteps = clientCmd.m_physSimParamArgs.m_numSimulationSubSteps; m_data->m_numSimulationSubSteps = clientCmd.m_physSimParamArgs.m_numSimulationSubSteps;
@@ -3351,7 +3355,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
{ {
btScalar desiredVelocity = 0.f; btScalar desiredVelocity = 0.f;
btScalar desiredPosition = q_new[link]; btScalar desiredPosition = q_new[link];
motor->setRhsClamp(gRhsClamp); //motor->setRhsClamp(gRhsClamp);
//printf("link %d: %f", link, q_new[link]); //printf("link %d: %f", link, q_new[link]);
motor->setVelocityTarget(desiredVelocity,1.0); motor->setVelocityTarget(desiredVelocity,1.0);
motor->setPositionTarget(desiredPosition,0.6); motor->setPositionTarget(desiredPosition,0.6);