tweak color of quadruped robot URDF, tweak quadruped.py script to make it more compatible with VR demo
allow VR physics server to run with or without 'realTimeSimulation'
This commit is contained in:
@@ -5,8 +5,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".226 0.16 .07"/>
|
<box size=".226 0.16 .07"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="black">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0 0 0 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -26,9 +26,7 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.026" radius="0.0434"/>
|
<cylinder length="0.026" radius="0.0434"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="black"/>
|
||||||
<color rgba="0 0 .8 1"/>
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<geometry>
|
<geometry>
|
||||||
@@ -55,9 +53,7 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.026" radius="0.0434"/>
|
<cylinder length="0.026" radius="0.0434"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="black"/>
|
||||||
<color rgba="0 0 .8 1"/>
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<geometry>
|
<geometry>
|
||||||
@@ -84,9 +80,7 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.026" radius="0.0434"/>
|
<cylinder length="0.026" radius="0.0434"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="black"/>
|
||||||
<color rgba="0 0 .8 1"/>
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<geometry>
|
<geometry>
|
||||||
@@ -113,9 +107,7 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.026" radius="0.0434"/>
|
<cylinder length="0.026" radius="0.0434"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="black"/>
|
||||||
<color rgba="0 0 .8 1"/>
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<geometry>
|
<geometry>
|
||||||
@@ -142,9 +134,7 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.026" radius="0.0434"/>
|
<cylinder length="0.026" radius="0.0434"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="black"/>
|
||||||
<color rgba="0 0 .8 1"/>
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<geometry>
|
<geometry>
|
||||||
@@ -171,9 +161,7 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.026" radius="0.0434"/>
|
<cylinder length="0.026" radius="0.0434"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="black"/>
|
||||||
<color rgba="0 0 .8 1"/>
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<geometry>
|
<geometry>
|
||||||
@@ -200,9 +188,7 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.026" radius="0.0434"/>
|
<cylinder length="0.026" radius="0.0434"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="black"/>
|
||||||
<color rgba="0 0 .8 1"/>
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<geometry>
|
<geometry>
|
||||||
@@ -229,9 +215,7 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.026" radius="0.0434"/>
|
<cylinder length="0.026" radius="0.0434"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="black"/>
|
||||||
<color rgba="0 0 .8 1"/>
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<geometry>
|
<geometry>
|
||||||
@@ -258,8 +242,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .11"/>
|
<box size=".01 0.01 .11"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -286,8 +270,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .11"/>
|
<box size=".01 0.01 .11"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -315,8 +299,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .2"/>
|
<box size=".01 0.01 .2"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -345,8 +329,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .2"/>
|
<box size=".01 0.01 .2"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -374,8 +358,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .11"/>
|
<box size=".01 0.01 .11"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -402,8 +386,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .11"/>
|
<box size=".01 0.01 .11"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -431,8 +415,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .2"/>
|
<box size=".01 0.01 .2"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -461,8 +445,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .2"/>
|
<box size=".01 0.01 .2"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -493,8 +477,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .11"/>
|
<box size=".01 0.01 .11"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -521,8 +505,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .11"/>
|
<box size=".01 0.01 .11"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -550,8 +534,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .2"/>
|
<box size=".01 0.01 .2"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -580,8 +564,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .2"/>
|
<box size=".01 0.01 .2"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -609,8 +593,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .11"/>
|
<box size=".01 0.01 .11"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -637,8 +621,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .11"/>
|
<box size=".01 0.01 .11"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -666,8 +650,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .2"/>
|
<box size=".01 0.01 .2"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
@@ -696,8 +680,8 @@
|
|||||||
<geometry>
|
<geometry>
|
||||||
<box size=".01 0.01 .2"/>
|
<box size=".01 0.01 .2"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="grey">
|
||||||
<color rgba="0 0 .8 1"/>
|
<color rgba="0.65 0.65 0.75 1"/>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
|
|||||||
@@ -4030,6 +4030,12 @@ int gDroppedSimulationSteps = 0;
|
|||||||
int gNumSteps = 0;
|
int gNumSteps = 0;
|
||||||
double gDtInSec = 0.f;
|
double gDtInSec = 0.f;
|
||||||
double gSubStep = 0.f;
|
double gSubStep = 0.f;
|
||||||
|
|
||||||
|
void PhysicsServerCommandProcessor::enableRealTimeSimulation(bool enableRealTimeSim)
|
||||||
|
{
|
||||||
|
m_data->m_allowRealTimeSimulation = enableRealTimeSim;
|
||||||
|
}
|
||||||
|
|
||||||
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||||
{
|
{
|
||||||
if (gResetSimulation)
|
if (gResetSimulation)
|
||||||
@@ -4038,7 +4044,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
|||||||
gResetSimulation = false;
|
gResetSimulation = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((gEnableRealTimeSimVR || m_data->m_allowRealTimeSimulation) && m_data->m_guiHelper)
|
if ((m_data->m_allowRealTimeSimulation) && m_data->m_guiHelper)
|
||||||
{
|
{
|
||||||
|
|
||||||
///this hardcoded C++ scene creation is temporary for demo purposes. It will be done in Python later...
|
///this hardcoded C++ scene creation is temporary for demo purposes. It will be done in Python later...
|
||||||
|
|||||||
@@ -85,6 +85,7 @@ public:
|
|||||||
void replayFromLogFile(const char* fileName);
|
void replayFromLogFile(const char* fileName);
|
||||||
void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes );
|
void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes );
|
||||||
void stepSimulationRealTime(double dtInSec);
|
void stepSimulationRealTime(double dtInSec);
|
||||||
|
void enableRealTimeSimulation(bool enableRealTimeSim);
|
||||||
void applyJointDamping(int bodyUniqueId);
|
void applyJointDamping(int bodyUniqueId);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -1584,7 +1584,11 @@ void PhysicsServerExample::renderScene()
|
|||||||
|
|
||||||
if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
|
if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
|
||||||
{
|
{
|
||||||
gEnableRealTimeSimVR = true;
|
if (!gEnableRealTimeSimVR)
|
||||||
|
{
|
||||||
|
gEnableRealTimeSimVR = true;
|
||||||
|
m_physicsServer.enableRealTimeSimulation(1);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -1819,8 +1823,6 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
|
|||||||
void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis)
|
void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis)
|
||||||
{
|
{
|
||||||
|
|
||||||
gEnableRealTimeSimVR = true;
|
|
||||||
|
|
||||||
if (controllerId <= 0 || controllerId >= MAX_VR_CONTROLLERS)
|
if (controllerId <= 0 || controllerId >= MAX_VR_CONTROLLERS)
|
||||||
{
|
{
|
||||||
printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS);
|
printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS);
|
||||||
|
|||||||
@@ -241,6 +241,12 @@ void PhysicsServerSharedMemory::stepSimulationRealTime(double dtInSec)
|
|||||||
m_data->m_commandProcessor->stepSimulationRealTime(dtInSec);
|
m_data->m_commandProcessor->stepSimulationRealTime(dtInSec);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PhysicsServerSharedMemory::enableRealTimeSimulation(bool enableRealTimeSim)
|
||||||
|
{
|
||||||
|
m_data->m_commandProcessor->enableRealTimeSimulation(enableRealTimeSim);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void PhysicsServerSharedMemory::processClientCommands()
|
void PhysicsServerSharedMemory::processClientCommands()
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -28,6 +28,8 @@ public:
|
|||||||
|
|
||||||
virtual void stepSimulationRealTime(double dtInSec);
|
virtual void stepSimulationRealTime(double dtInSec);
|
||||||
|
|
||||||
|
virtual void enableRealTimeSimulation(bool enableRealTimeSim);
|
||||||
|
|
||||||
//bool supportsJointMotor(class btMultiBody* body, int linkIndex);
|
//bool supportsJointMotor(class btMultiBody* body, int linkIndex);
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -4,9 +4,10 @@ import math
|
|||||||
|
|
||||||
p.connect(p.SHARED_MEMORY)
|
p.connect(p.SHARED_MEMORY)
|
||||||
p.loadURDF("plane.urdf")
|
p.loadURDF("plane.urdf")
|
||||||
quadruped = p.loadURDF("quadruped/quadruped.urdf",0,0,.3)
|
p.setGravity(0,0,-1)
|
||||||
|
p.setRealTimeSimulation(0)
|
||||||
|
quadruped = p.loadURDF("quadruped/quadruped.urdf",10,-2,2)
|
||||||
#p.getNumJoints(1)
|
#p.getNumJoints(1)
|
||||||
|
|
||||||
#right front leg
|
#right front leg
|
||||||
p.resetJointState(quadruped,0,1.57)
|
p.resetJointState(quadruped,0,1.57)
|
||||||
p.resetJointState(quadruped,2,-2.2)
|
p.resetJointState(quadruped,2,-2.2)
|
||||||
@@ -64,16 +65,17 @@ p.setJointMotorControl(quadruped,21,p.POSITION_CONTROL,-1.57,1)
|
|||||||
p.setJointMotorControl(quadruped,22,p.VELOCITY_CONTROL,0,0)
|
p.setJointMotorControl(quadruped,22,p.VELOCITY_CONTROL,0,0)
|
||||||
p.setJointMotorControl(quadruped,23,p.VELOCITY_CONTROL,0,0)
|
p.setJointMotorControl(quadruped,23,p.VELOCITY_CONTROL,0,0)
|
||||||
|
|
||||||
p.setGravity(0,0,-10)
|
|
||||||
|
|
||||||
p_gain = 2
|
p_gain = 2
|
||||||
speed = 10
|
speed = 10
|
||||||
amplitude = 1.3
|
amplitude = 1.3
|
||||||
|
|
||||||
#stand still
|
#stand still
|
||||||
t_end = time.time() + 5
|
t_end = time.time() + 2
|
||||||
while time.time() < t_end:
|
while time.time() < t_end:
|
||||||
p.stepSimulation()
|
p.stepSimulation()
|
||||||
|
p.setGravity(0,0,-10)
|
||||||
|
|
||||||
jump_amp = 0.5
|
jump_amp = 0.5
|
||||||
|
|
||||||
@@ -125,4 +127,4 @@ while time.time() < t_end:
|
|||||||
p.setJointMotorControl(quadruped,21,p.POSITION_CONTROL,-1.57,1)
|
p.setJointMotorControl(quadruped,21,p.POSITION_CONTROL,-1.57,1)
|
||||||
|
|
||||||
p.stepSimulation()
|
p.stepSimulation()
|
||||||
|
p.setRealTimeSimulation(1)
|
||||||
|
|||||||
Reference in New Issue
Block a user