Merge pull request #703 from erwincoumans/master

OpenVR controller can pick/drag objects
This commit is contained in:
erwincoumans
2016-07-18 11:46:53 -07:00
committed by GitHub
47 changed files with 2460 additions and 69 deletions

View File

@@ -14,6 +14,6 @@ rem cd vs2010
rem rename 0_Bullet3Solution.sln 0_client.sln rem rename 0_Bullet3Solution.sln 0_client.sln
rem cd .. rem cd ..
rem rename vs2010 vs2010_client rem rename vs2010 vs2010_client
start vs2010/0_Bullet3Solution.sln rem start vs2010/0_Bullet3Solution.sln
pause pause

View File

@@ -0,0 +1,62 @@
<?xml version="1.0" ?>
<!-- adapted from Daniel Mellinger, Nathan Michael, Vijay Kumar, "Trajectory Generation and Control for Precise Aggressive Maneuvers with Quadrotors" -->
<robot xmlns="http://drake.mit.edu"
xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:schemaLocation="http://drake.mit.edu ../../../../pods/drake/doc/drakeURDF.xsd" name="quadrotor">
<link name="base_link">
<inertial>
<mass value="0.5"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.0023" ixy="0.0" ixz="0.0" iyy="0.0023" iyz="0.0" izz="0.004"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="quadrotor_base.obj" scale=".1 .1 .1"/>
</geometry>
</visual>
<!-- note: the original hector quadrotor urdf had a (simplified, but still complex) collision mesh, too -->
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius=".3" length=".1"/>
</geometry>
</collision>
</link>
<frame link="base_link" name="body" rpy="0 0 0" xyz="0 0 0" />
<force_element name="prop1">
<propellor lower_limit="0" upper_limit="10" scale_factor_thrust="1.0" scale_factor_moment="0.0245">
<parent link="base_link"/>
<origin xyz=".1750 0 0"/>
<axis xyz="0 0 1"/>
</propellor>
</force_element>
<force_element name="prop2">
<propellor lower_limit="0" upper_limit="10" scale_factor_thrust="1.0" scale_factor_moment="-0.0245">
<parent link="base_link"/>
<origin xyz="0 .1750 0 "/>
<axis xyz="0 0 1"/>
</propellor>
</force_element>
<force_element name="prop3">
<propellor lower_limit="0" upper_limit="10" scale_factor_thrust="1.0" scale_factor_moment="0.0245">
<parent link="base_link"/>
<origin xyz="-.1750 0 0"/>
<axis xyz="0 0 1"/>
</propellor>
</force_element>
<force_element name="prop4">
<propellor lower_limit="0" upper_limit="10" scale_factor_thrust="1.0" scale_factor_moment="-0.0245">
<parent link="base_link"/>
<origin xyz="0 -.1750 0"/>
<axis xyz="0 0 1"/>
</propellor>
</force_element>
</robot>

File diff suppressed because it is too large Load Diff

BIN
data/checker_blue.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 6.2 KiB

345
data/husky/husky.urdf Normal file
View File

@@ -0,0 +1,345 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from ../urdf/husky.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<!--
Software License Agreement (BSD)
\file husky.urdf.xacro
\authors Paul Bovbel <pbovbel@clearpathrobotics.com>
\copyright Copyright (c) 2015, Clearpath Robotics, Inc., All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that
the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list of conditions and the
following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
following disclaimer in the documentation and/or other materials provided with the distribution.
* Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<robot name="husky_robot" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Included URDF/XACRO Files -->
<material name="Black">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
<material name="Blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="Green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="Grey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<material name="DarkGrey">
<color rgba="0.3 0.3 0.3 1.0"/>
</material>
<material name="Red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="White">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<material name="Yellow">
<color rgba="0.8 0.8 0.0 1.0"/>
</material>
<!-- Base Size -->
<!-- Wheel Mounting Positions -->
<!-- Wheel Properties -->
<!-- Base link is on the ground under the robot -->
<link name="base_footprint"/>
<gazebo reference="base_footprint">
<material>Gazebo/DarkGrey</material>
</gazebo>
<joint name="chassis_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.14493"/>
<parent link="base_footprint"/>
<child link="base_link"/>
</joint>
<!-- Chassis link is the center of the robot's bottom plate -->
<link name="base_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_link.stl"/>
</geometry>
<material name="Black"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.12498"/>
<geometry>
<!-- Make collision box slightly bigger in x and z directions. -->
<box size="1.0074 0.5709 0.2675"/>
</geometry>
</collision>
<inertial>
<mass value="33.455"/>
<origin xyz="-0.08748 -0.00085 0.09947"/>
<inertia ixx="0.6022" ixy="-0.02364" ixz="-0.1197" iyy="1.7386" iyz="-0.001544" izz="2.0296"/>
</inertial>
</link>
<gazebo reference="base_link">
</gazebo>
<!-- IMU Link is the standard mounting position for the UM6 IMU.-->
<!-- Can be modified with environment variables in /etc/ros/setup.bash -->
<link name="imu_link"/>
<joint name="imu_joint" type="fixed">
<origin rpy="$(optenv HUSKY_IMU_RPY 0 -1.5708 3.1416)" xyz="$(optenv HUSKY_IMU_XYZ 0.19 0 0.149)"/>
<parent link="base_link"/>
<child link="imu_link"/>
</joint>
<gazebo reference="imu_link">
</gazebo>
<!-- Husky wheel macros -->
<link name="front_left_wheel_link">
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/wheel.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.1143" radius="0.17775"/>
</geometry>
</collision>
</link>
<gazebo reference="front_left_wheel_link">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="front_left_wheel" type="continuous">
<parent link="base_link"/>
<child link="front_left_wheel_link"/>
<origin rpy="0 0 0" xyz="0.256 0.2854 0.03282"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<transmission name="front_left_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="front_left_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="front_left_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<link name="front_right_wheel_link">
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/wheel.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.1143" radius="0.17775"/>
</geometry>
</collision>
</link>
<gazebo reference="front_right_wheel_link">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="front_right_wheel" type="continuous">
<parent link="base_link"/>
<child link="front_right_wheel_link"/>
<origin rpy="0 0 0" xyz="0.256 -0.2854 0.03282"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<transmission name="front_right_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="front_right_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="front_right_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<link name="rear_left_wheel_link">
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/wheel.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.1143" radius="0.17775"/>
</geometry>
</collision>
</link>
<gazebo reference="rear_left_wheel_link">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="rear_left_wheel" type="continuous">
<parent link="base_link"/>
<child link="rear_left_wheel_link"/>
<origin rpy="0 0 0" xyz="-0.256 0.2854 0.03282"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<transmission name="rear_left_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="rear_left_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="rear_left_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<link name="rear_right_wheel_link">
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/wheel.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.1143" radius="0.17775"/>
</geometry>
</collision>
</link>
<gazebo reference="rear_right_wheel_link">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="rear_right_wheel" type="continuous">
<parent link="base_link"/>
<child link="rear_right_wheel_link"/>
<origin rpy="0 0 0" xyz="-0.256 -0.2854 0.03282"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<transmission name="rear_right_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="rear_right_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="rear_right_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<link name="top_plate_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/top_plate.stl"/>
</geometry>
<material name="Yellow"/>
</visual>
</link>
<joint name="top_plate" type="fixed">
<parent link="base_link"/>
<child link="top_plate_link"/>
</joint>
<gazebo reference="top_plate_link">
<material>Gazebo/Yellow</material>
</gazebo>
<link name="user_rail_link">
<visual>
<geometry>
<mesh filename="meshes/user_rail.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
</link>
<joint name="user_rail" type="fixed">
<origin rpy="0 0 0" xyz="0.272 0 0.245"/>
<parent link="base_link"/>
<child link="user_rail_link"/>
</joint>
<gazebo reference="user_rail_link">
<material>Gazebo/DarkGrey</material>
</gazebo>
<link name="front_bumper_link">
<visual>
<geometry>
<mesh filename="meshes/bumper.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
</link>
<joint name="front_bumper" type="fixed">
<origin rpy="0 0 0" xyz="0.48 0 0.091"/>
<parent link="base_link"/>
<child link="front_bumper_link"/>
</joint>
<gazebo reference="front_bumper_link">
<material>Gazebo/DarkGrey</material>
</gazebo>
<link name="rear_bumper_link">
<visual>
<geometry>
<mesh filename="meshes/bumper.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
</link>
<joint name="rear_bumper" type="fixed">
<origin rpy="0 0 3.14159" xyz="-0.48 0 0.091"/>
<parent link="base_link"/>
<child link="rear_bumper_link"/>
</joint>
<gazebo reference="rear_bumper_link">
<material>Gazebo/DarkGrey</material>
</gazebo>
</robot>

Binary file not shown.

Binary file not shown.

Binary file not shown.

BIN
data/husky/meshes/wheel.stl Normal file

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@@ -77,7 +77,7 @@
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/coarse/link_0.stl"/> <mesh filename="meshes/link_0.stl"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
@@ -106,7 +106,7 @@
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/coarse/link_1.stl"/> <mesh filename="meshes/link_1.stl"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
@@ -135,7 +135,7 @@
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/coarse/link_2.stl"/> <mesh filename="meshes/link_2.stl"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
@@ -164,7 +164,7 @@
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/coarse/link_3.stl"/> <mesh filename="meshes/link_3.stl"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
@@ -193,7 +193,7 @@
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/coarse/link_4.stl"/> <mesh filename="meshes/link_4.stl"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
@@ -222,7 +222,7 @@
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/coarse/link_5.stl"/> <mesh filename="meshes/link_5.stl"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
@@ -251,7 +251,7 @@
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/coarse/link_6.stl"/> <mesh filename="meshes/link_6.stl"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
@@ -280,7 +280,7 @@
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/coarse/link_7.stl"/> <mesh filename="meshes/link_7.stl"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>

View File

@@ -10,6 +10,6 @@ newmtl Material
Ks 0.0000 0.0000 0.0000 Ks 0.0000 0.0000 0.0000
Ke 0.0000 0.0000 0.0000 Ke 0.0000 0.0000 0.0000
map_Ka cube.tga map_Ka cube.tga
map_Kd checker_grid.jpg map_Kd checker_blue.png

View File

@@ -7,9 +7,9 @@ v 5.000000 5.000000 0.000000
v -5.000000 5.000000 0.000000 v -5.000000 5.000000 0.000000
v -5.000000 -5.000000 0.000000 v -5.000000 -5.000000 0.000000
vt 1.000000 0.000000 vt 5.000000 0.000000
vt 1.000000 1.000000 vt 5.000000 5.000000
vt 0.000000 1.000000 vt 0.000000 5.000000
vt 0.000000 0.000000 vt 0.000000 0.000000
usemtl Material usemtl Material

View File

@@ -2,11 +2,21 @@
# www.blender.org # www.blender.org
mtllib plane.mtl mtllib plane.mtl
o Plane o Plane
v 100.000000 0.000000 -100.000000 v 100.000000 -100.000000 0.000000
v 100.000000 0.000000 100.000000 v 100.000000 100.000000 0.000000
v -100.000000 0.000000 100.000000 v -100.000000 100.000000 0.000000
v -100.000000 0.000000 -100.000000 v -100.000000 -100.000000 0.000000
vt 100.000000 0.000000
vt 100.000000 100.000000
vt 0.000000 100.000000
vt 0.000000 0.000000
usemtl Material usemtl Material
s off s off
f 3 2 1 f 1/1 2/2 3/3
f 4 3 1 f 1/1 3/3 4/4

26
data/plane100.urdf Normal file
View File

@@ -0,0 +1,26 @@
<?xml version="0.0" ?>
<robot name="cube.urdf">
<link name="baseLink">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".0"/>
<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="plane100.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="10 10 0.001"/>
</geometry>
</collision>
</link>
</robot>

View File

@@ -46,6 +46,8 @@ public:
virtual bool mouseButtonCallback(int button, int state, float x, float y)=0; virtual bool mouseButtonCallback(int button, int state, float x, float y)=0;
virtual bool keyboardCallback(int key, int state)=0; virtual bool keyboardCallback(int key, int state)=0;
virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4]) {}
virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]){}
}; };
class ExampleEntries class ExampleEntries

View File

@@ -187,7 +187,7 @@ static ExampleEntry gDefaultExamples[]=
#endif //INCLUDE_CLOTH_DEMOS #endif //INCLUDE_CLOTH_DEMOS
///we disable the benchmarks in debug mode, they are way too slow and benchmarking in debug mode is not recommended ///we disable the benchmarks in debug mode, they are way too slow and benchmarking in debug mode is not recommended
#ifndef _DEBUG //#ifndef _DEBUG
ExampleEntry(0,"Benchmarks"), ExampleEntry(0,"Benchmarks"),
ExampleEntry(1,"3000 boxes", "Benchmark a stack of 3000 boxes. It will stress the collision detection, a specialized box-box implementation based on the separating axis test, and the constraint solver. ", BenchmarkCreateFunc, 1), ExampleEntry(1,"3000 boxes", "Benchmark a stack of 3000 boxes. It will stress the collision detection, a specialized box-box implementation based on the separating axis test, and the constraint solver. ", BenchmarkCreateFunc, 1),
ExampleEntry(1,"1000 stack", "Benchmark a stack of 3000 boxes. It will stress the collision detection, a specialized box-box implementation based on the separating axis test, and the constraint solver. ", ExampleEntry(1,"1000 stack", "Benchmark a stack of 3000 boxes. It will stress the collision detection, a specialized box-box implementation based on the separating axis test, and the constraint solver. ",
@@ -197,7 +197,7 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(1,"Prim vs Mesh", "Benchmark the performance and stability of rigid bodies using primitive collision shapes (btSphereShape, btBoxShape), resting on a triangle mesh, btBvhTriangleMeshShape.", BenchmarkCreateFunc, 5), ExampleEntry(1,"Prim vs Mesh", "Benchmark the performance and stability of rigid bodies using primitive collision shapes (btSphereShape, btBoxShape), resting on a triangle mesh, btBvhTriangleMeshShape.", BenchmarkCreateFunc, 5),
ExampleEntry(1,"Convex vs Mesh", "Benchmark the performance and stability of rigid bodies using convex hull collision shapes (btConvexHullShape), resting on a triangle mesh, btBvhTriangleMeshShape.", BenchmarkCreateFunc, 6), ExampleEntry(1,"Convex vs Mesh", "Benchmark the performance and stability of rigid bodies using convex hull collision shapes (btConvexHullShape), resting on a triangle mesh, btBvhTriangleMeshShape.", BenchmarkCreateFunc, 6),
ExampleEntry(1,"Raycast", "Benchmark the performance of the btCollisionWorld::rayTest. Note that currently the rays are not rendered.", BenchmarkCreateFunc, 7), ExampleEntry(1,"Raycast", "Benchmark the performance of the btCollisionWorld::rayTest. Note that currently the rays are not rendered.", BenchmarkCreateFunc, 7),
#endif //#endif

View File

@@ -16,9 +16,9 @@ subject to the following restrictions:
///todo: make this configurable in the gui ///todo: make this configurable in the gui
bool useShadowMap=true;//false;//true; bool useShadowMap = true;// true;//false;//true;
int shadowMapWidth=4096;//8192; int shadowMapWidth=4096;//8192;
int shadowMapHeight=4096; int shadowMapHeight= 4096;
float shadowMapWorldSize=25; float shadowMapWorldSize=25;
#define MAX_POINTS_IN_BATCH 1024 #define MAX_POINTS_IN_BATCH 1024
@@ -363,7 +363,7 @@ void GLInstancingRenderer::writeSingleInstanceScaleToCPU(double* scale, int srcI
void GLInstancingRenderer::writeSingleInstanceTransformToGPU(float* position, float* orientation, int objectIndex) void GLInstancingRenderer::writeSingleInstanceTransformToGPU(float* position, float* orientation, int objectIndex)
{ {
glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo); glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo);
glFlush(); //glFlush();
char* orgBase = (char*)glMapBuffer( GL_ARRAY_BUFFER,GL_READ_WRITE); char* orgBase = (char*)glMapBuffer( GL_ARRAY_BUFFER,GL_READ_WRITE);
//b3GraphicsInstance* gfxObj = m_graphicsInstances[k]; //b3GraphicsInstance* gfxObj = m_graphicsInstances[k];
@@ -393,7 +393,7 @@ void GLInstancingRenderer::writeSingleInstanceTransformToGPU(float* position, fl
orientations [objectIndex*4+3] = orientation[3]; orientations [objectIndex*4+3] = orientation[3];
glUnmapBuffer( GL_ARRAY_BUFFER); glUnmapBuffer( GL_ARRAY_BUFFER);
glFlush(); //glFlush();
} }
@@ -500,7 +500,7 @@ void GLInstancingRenderer::writeTransforms()
glUnmapBuffer( GL_ARRAY_BUFFER); glUnmapBuffer( GL_ARRAY_BUFFER);
//if this glFinish is removed, the animation is not always working/blocks //if this glFinish is removed, the animation is not always working/blocks
//@todo: figure out why //@todo: figure out why
glFlush(); //glFlush();
#endif #endif
@@ -1037,7 +1037,7 @@ void GLInstancingRenderer::renderScene()
//avoid some Intel driver on a Macbook Pro to lock-up //avoid some Intel driver on a Macbook Pro to lock-up
//todo: figure out what is going on on that machine //todo: figure out what is going on on that machine
glFlush(); //glFlush();
if (useShadowMap) if (useShadowMap)
{ {
@@ -1539,7 +1539,7 @@ b3Assert(glGetError() ==GL_NO_ERROR);
B3_PROFILE("glFlush2"); B3_PROFILE("glFlush2");
glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo); glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo);
glFlush(); //glFlush();
} }
b3Assert(glGetError() ==GL_NO_ERROR); b3Assert(glGetError() ==GL_NO_ERROR);
@@ -1730,7 +1730,7 @@ b3Assert(glGetError() ==GL_NO_ERROR);
{ {
B3_PROFILE("glFlush"); B3_PROFILE("glFlush");
glFlush(); //glFlush();
} }
if (renderMode==B3_CREATE_SHADOWMAP_RENDERMODE) if (renderMode==B3_CREATE_SHADOWMAP_RENDERMODE)
{ {

View File

@@ -115,6 +115,15 @@ int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, doub
return 0; return 0;
} }
int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
command->m_physSimParamArgs.m_allowRealTimeSimulation = enableRealTimeSimulation;
command->m_updateFlags |= SIM_PARAM_UPDATE_REAL_TIME_SIMULATION;
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

@@ -81,6 +81,7 @@ void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImage
b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient); b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz); int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz);
int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep); int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep);
int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation);
b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient); b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient);

View File

@@ -374,6 +374,8 @@ struct PhysicsServerCommandProcessorInternalData
///end handle management ///end handle management
bool m_allowRealTimeSimulation;
bool m_hasGround;
CommandLogger* m_commandLogger; CommandLogger* m_commandLogger;
CommandLogPlayback* m_logPlayback; CommandLogPlayback* m_logPlayback;
@@ -417,7 +419,8 @@ struct PhysicsServerCommandProcessorInternalData
TinyRendererVisualShapeConverter m_visualConverter; TinyRendererVisualShapeConverter m_visualConverter;
PhysicsServerCommandProcessorInternalData() PhysicsServerCommandProcessorInternalData()
: :m_hasGround(false),
m_allowRealTimeSimulation(false),
m_commandLogger(0), m_commandLogger(0),
m_logPlayback(0), m_logPlayback(0),
m_physicsDeltaTime(1./240.), m_physicsDeltaTime(1./240.),
@@ -496,6 +499,9 @@ void PhysicsServerCommandProcessor::setGuiHelper(struct GUIHelperInterface* guiH
} }
} }
m_data->m_guiHelper = guiHelper; m_data->m_guiHelper = guiHelper;
} }
@@ -504,6 +510,7 @@ PhysicsServerCommandProcessor::PhysicsServerCommandProcessor()
m_data = new PhysicsServerCommandProcessorInternalData(); m_data = new PhysicsServerCommandProcessorInternalData();
createEmptyDynamicsWorld(); createEmptyDynamicsWorld();
} }
PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor() PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor()
@@ -983,7 +990,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char*
bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes ) bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes )
{ {
bool hasStatus = false; bool hasStatus = false;
{ {
@@ -1768,6 +1775,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{ {
m_data->m_physicsDeltaTime = clientCmd.m_physSimParamArgs.m_deltaTime; m_data->m_physicsDeltaTime = clientCmd.m_physSimParamArgs.m_deltaTime;
} }
if (clientCmd.m_updateFlags & SIM_PARAM_UPDATE_REAL_TIME_SIMULATION)
{
m_data->m_allowRealTimeSimulation = clientCmd.m_physSimParamArgs.m_allowRealTimeSimulation;
}
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_GRAVITY) if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_GRAVITY)
{ {
btVector3 grav(clientCmd.m_physSimParamArgs.m_gravityAcceleration[0], btVector3 grav(clientCmd.m_physSimParamArgs.m_gravityAcceleration[0],
@@ -1873,7 +1884,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
SharedMemoryStatus& serverCmd =serverStatusOut; SharedMemoryStatus& serverCmd =serverStatusOut;
serverCmd.m_type = CMD_RESET_SIMULATION_COMPLETED; serverCmd.m_type = CMD_RESET_SIMULATION_COMPLETED;
hasStatus = true; hasStatus = true;
m_data->m_hasGround = false;
break; break;
} }
case CMD_CREATE_RIGID_BODY: case CMD_CREATE_RIGID_BODY:
@@ -2307,6 +2318,26 @@ void PhysicsServerCommandProcessor::replayFromLogFile(const char* fileName)
m_data->m_logPlayback = pb; m_data->m_logPlayback = pb;
} }
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
{
if (m_data->m_allowRealTimeSimulation)
{
if (!m_data->m_hasGround)
{
m_data->m_hasGround = true;
int bodyId = 0;
btAlignedObjectArray<char> bufferServerToClient;
bufferServerToClient.resize(32768);
loadUrdf("plane.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, true, &bodyId, &bufferServerToClient[0], bufferServerToClient.size());
}
m_data->m_dynamicsWorld->stepSimulation(dtInSec);
}
}
void PhysicsServerCommandProcessor::applyJointDamping(int bodyUniqueId) void PhysicsServerCommandProcessor::applyJointDamping(int bodyUniqueId)
{ {
InteralBodyData* body = m_data->getHandle(bodyUniqueId); InteralBodyData* body = m_data->getHandle(bodyUniqueId);

View File

@@ -53,7 +53,8 @@ public:
void enableCommandLogging(bool enable, const char* fileName); void enableCommandLogging(bool enable, const char* fileName);
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 applyJointDamping(int bodyUniqueId); void applyJointDamping(int bodyUniqueId);
}; };

View File

@@ -9,11 +9,12 @@
#include "PhysicsServerSharedMemory.h" #include "PhysicsServerSharedMemory.h"
#include "SharedMemoryCommon.h" #include "SharedMemoryCommon.h"
#include "Bullet3Common/b3Matrix3x3.h"
#include "../Utils/b3Clock.h" #include "../Utils/b3Clock.h"
#include "../MultiThreading/b3ThreadSupportInterface.h" #include "../MultiThreading/b3ThreadSupportInterface.h"
void MotionThreadFunc(void* userPtr,void* lsMemory); void MotionThreadFunc(void* userPtr,void* lsMemory);
void* MotionlsMemoryFunc(); void* MotionlsMemoryFunc();
#define MAX_MOTION_NUM_THREADS 1 #define MAX_MOTION_NUM_THREADS 1
@@ -80,13 +81,23 @@ b3ThreadSupportInterface* createMotionThreadSupport(int numThreads)
struct MotionArgs struct MotionArgs
{ {
MotionArgs() MotionArgs()
:m_physicsServerPtr(0) :m_physicsServerPtr(0),
m_isPicking(false),
m_isDragging(false),
m_isReleasing(false)
{ {
} }
b3CriticalSection* m_cs; b3CriticalSection* m_cs;
PhysicsServerSharedMemory* m_physicsServerPtr; PhysicsServerSharedMemory* m_physicsServerPtr;
b3AlignedObjectArray<b3Vector3> m_positions; b3AlignedObjectArray<b3Vector3> m_positions;
btVector3 m_pos;
btQuaternion m_orn;
bool m_isPicking;
bool m_isDragging;
bool m_isReleasing;
}; };
struct MotionThreadLocalStorage struct MotionThreadLocalStorage
@@ -113,23 +124,58 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
args->m_cs->setSharedParam(0,eMotionIsInitialized); args->m_cs->setSharedParam(0,eMotionIsInitialized);
args->m_cs->unlock(); args->m_cs->unlock();
do do
{ {
//todo(erwincoumans): do we want some sleep to reduce CPU resources in this thread? //todo(erwincoumans): do we want some sleep to reduce CPU resources in this thread?
#if 0
double deltaTimeInSeconds = double(clock.getTimeMicroseconds())/1000000.; double deltaTimeInSeconds = double(clock.getTimeMicroseconds())/1000000.;
if (deltaTimeInSeconds<(1./260.)) if (deltaTimeInSeconds<(1./5000.))
{ {
skip++; skip++;
if (deltaTimeInSeconds<.001) } else
continue; {
//process special controller commands, such as
//VR controller button press/release and controller motion
btVector3 from = args->m_pos;
btMatrix3x3 mat(args->m_orn);
btVector3 toX = args->m_pos+mat.getColumn(0);
btVector3 toY = args->m_pos+mat.getColumn(1);
btVector3 toZ = args->m_pos+mat.getColumn(2)*50.;
if (args->m_isPicking)
{
args->m_isPicking = false;
args->m_isDragging = true;
args->m_physicsServerPtr->pickBody(from,-toZ);
//printf("PICK!\n");
}
if (args->m_isDragging)
{
args->m_physicsServerPtr->movePickedBody(from,-toZ);
// printf(".");
}
if (args->m_isReleasing)
{
args->m_isDragging = false;
args->m_isReleasing = false;
args->m_physicsServerPtr->removePickingConstraint();
//printf("Release pick\n");
}
//don't simulate over a huge timestep if we had some interruption (debugger breakpoint etc)
btClamp(deltaTimeInSeconds,0.,0.1);
args->m_physicsServerPtr->stepSimulationRealTime(deltaTimeInSeconds);
clock.reset();
} }
clock.reset();
#endif
args->m_physicsServerPtr->processClientCommands(); args->m_physicsServerPtr->processClientCommands();
} while (args->m_cs->getSharedParam(0)!=eRequestTerminateMotion); } while (args->m_cs->getSharedParam(0)!=eRequestTerminateMotion);
} else } else
{ {
@@ -375,7 +421,7 @@ class PhysicsServerExample : public SharedMemoryCommon
btClock m_clock; btClock m_clock;
bool m_replay; bool m_replay;
int m_options; int m_options;
public: public:
PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, SharedMemoryInterface* sharedMem=0, int options=0); PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, SharedMemoryInterface* sharedMem=0, int options=0);
@@ -417,6 +463,9 @@ public:
btVector3 getRayTo(int x,int y); btVector3 getRayTo(int x,int y);
virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]);
virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4]);
virtual bool mouseMoveCallback(float x,float y) virtual bool mouseMoveCallback(float x,float y)
{ {
if (m_replay) if (m_replay)
@@ -720,6 +769,28 @@ void PhysicsServerExample::renderScene()
//m_args[0].m_cs->lock(); //m_args[0].m_cs->lock();
m_physicsServer.renderScene(); m_physicsServer.renderScene();
if (m_args[0].m_isPicking || m_args[0].m_isDragging)
{
btVector3 from = m_args[0].m_pos;
btMatrix3x3 mat(m_args[0].m_orn);
btVector3 toX = m_args[0].m_pos+mat.getColumn(0);
btVector3 toY = m_args[0].m_pos+mat.getColumn(1);
btVector3 toZ = m_args[0].m_pos+mat.getColumn(2);
int width = 2;
btVector4 color;
color=btVector4(1,0,0,1);
m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toX,color,width);
color=btVector4(0,1,0,1);
m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toY,color,width);
color=btVector4(0,0,1,1);
m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toZ,color,width);
}
if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera()) if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
{ {
@@ -856,4 +927,17 @@ class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOpt
} }
B3_STANDALONE_EXAMPLE(PhysicsServerCreateFunc) void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orn[4])
{
m_args[0].m_isPicking = (state!=0);
m_args[0].m_isReleasing = (state==0);
m_args[0].m_pos.setValue(pos[0],pos[1],pos[2]);
m_args[0].m_orn.setValue(orn[0],orn[1],orn[2],orn[3]);
}
void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4])
{
m_args[0].m_pos.setValue(pos[0],pos[1],pos[2]);
m_args[0].m_orn.setValue(orn[0],orn[1],orn[2],orn[3]);
}
B3_STANDALONE_EXAMPLE(PhysicsServerCreateFunc)

View File

@@ -236,8 +236,10 @@ void PhysicsServerSharedMemory::releaseSharedMemory()
} }
void PhysicsServerSharedMemory::stepSimulationRealTime(double dtInSec)
{
m_data->m_commandProcessor->stepSimulationRealTime(dtInSec);
}
void PhysicsServerSharedMemory::processClientCommands() void PhysicsServerSharedMemory::processClientCommands()

View File

@@ -26,6 +26,8 @@ public:
virtual void processClientCommands(); virtual void processClientCommands();
virtual void stepSimulationRealTime(double dtInSec);
//bool supportsJointMotor(class btMultiBody* body, int linkIndex); //bool supportsJointMotor(class btMultiBody* body, int linkIndex);
//@todo(erwincoumans) Should we have shared memory commands for picking objects? //@todo(erwincoumans) Should we have shared memory commands for picking objects?

View File

@@ -215,6 +215,7 @@ enum EnumSimParamUpdateFlags
SIM_PARAM_UPDATE_GRAVITY=2, SIM_PARAM_UPDATE_GRAVITY=2,
SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS=4, SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS=4,
SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS=8, SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS=8,
SIM_PARAM_UPDATE_REAL_TIME_SIMULATION = 16,
}; };
///Controlling a robot involves sending the desired state to its joint motor controllers. ///Controlling a robot involves sending the desired state to its joint motor controllers.
@@ -225,6 +226,7 @@ struct SendPhysicsSimulationParameters
double m_gravityAcceleration[3]; double m_gravityAcceleration[3];
int m_numSimulationSubSteps; int m_numSimulationSubSteps;
int m_numSolverIterations; int m_numSolverIterations;
bool m_allowRealTimeSimulation;
}; };
struct RequestActualStateArgs struct RequestActualStateArgs

View File

@@ -4,6 +4,8 @@
#include "../OpenGLWindow/SimpleOpenGL3App.h" #include "../OpenGLWindow/SimpleOpenGL3App.h"
#include "../OpenGLWindow/OpenGLInclude.h" #include "../OpenGLWindow/OpenGLInclude.h"
#include "Bullet3Common/b3Quaternion.h" #include "Bullet3Common/b3Quaternion.h"
#include "Bullet3Common/b3Transform.h"
#include "../ExampleBrowser/OpenGLGuiHelper.h" #include "../ExampleBrowser/OpenGLGuiHelper.h"
#include "../CommonInterfaces/CommonExampleInterface.h" #include "../CommonInterfaces/CommonExampleInterface.h"
#include "../CommonInterfaces/CommonGUIHelperInterface.h" #include "../CommonInterfaces/CommonGUIHelperInterface.h"
@@ -28,6 +30,8 @@ int gSharedMemoryKey = -1;
#include "pathtools.h" #include "pathtools.h"
CommonExampleInterface* sExample; CommonExampleInterface* sExample;
int sIsPressed=-1;
int sPrevPacketNum=0;
GUIHelperInterface* sGuiPtr = 0; GUIHelperInterface* sGuiPtr = 0;
@@ -82,7 +86,7 @@ public:
bool BInit(); bool BInit();
bool BInitGL(); bool BInitGL();
bool BInitCompositor(); bool BInitCompositor();
void getControllerTransform(int unDevice, b3Transform& tr);
void SetupRenderModels(); void SetupRenderModels();
void Shutdown(); void Shutdown();
@@ -619,6 +623,26 @@ void CMainApplication::Shutdown()
} }
void CMainApplication::getControllerTransform(int unDevice, b3Transform& tr)
{
const Matrix4 & matOrg = m_rmat4DevicePose[unDevice];
tr.setIdentity();
tr.setOrigin(b3MakeVector3(matOrg[12],matOrg[13],matOrg[14]));//pos[1]));
b3Matrix3x3 bmat;
for (int i=0;i<3;i++)
{
for (int j=0;j<3;j++)
{
bmat[i][j] = matOrg[i+4*j];
}
}
tr.setBasis(bmat);
b3Transform y2z;
y2z.setIdentity();
y2z.setRotation(b3Quaternion(0,B3_HALF_PI,0));
tr = y2z*tr;
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
// Purpose: // Purpose:
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
@@ -639,14 +663,61 @@ bool CMainApplication::HandleInput()
vr::VRControllerState_t state; vr::VRControllerState_t state;
if( m_pHMD->GetControllerState( unDevice, &state ) ) if( m_pHMD->GetControllerState( unDevice, &state ) )
{ {
if (state.ulButtonPressed) uint64_t trigger = vr::ButtonMaskFromId(vr::k_EButton_SteamVR_Trigger);
if (sPrevPacketNum != state.unPacketNum)
{ {
b3Printf("state.ulButtonPressed=%d\n",state.ulButtonPressed);
sExample->exitPhysics(); static int counter=0;
m_app->m_instancingRenderer->removeAllInstances(); sPrevPacketNum = state.unPacketNum;
sExample->initPhysics(); //b3Printf(".");
bool isTrigger = (state.ulButtonPressed&trigger)!=0;
if (isTrigger)
{
//printf("unDevice=%d\n",unDevice);
b3Transform tr;
getControllerTransform(unDevice,tr);
float pos[3] = {tr.getOrigin()[0],tr.getOrigin()[1],tr.getOrigin()[2]};
b3Quaternion born = tr.getRotation();
float orn[4] = {born[0],born[1],born[2],born[3]};
if (sIsPressed!=unDevice)
{
b3Printf("trigger pressed %d, %d\n",counter++, unDevice);
sIsPressed=unDevice;
sExample->vrControllerButtonCallback(unDevice,1,1,pos, orn);
//
//virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4]) {}
//virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]){}
//sExample->start
} else
{
sExample->vrControllerMoveCallback(unDevice,pos,orn);
}
//sExample->exitPhysics();
//m_app->m_instancingRenderer->removeAllInstances();
///sExample->initPhysics();
} else
{
if (unDevice==sIsPressed)
{
b3Transform tr;
getControllerTransform(unDevice,tr);
float pos[3] = {tr.getOrigin()[0],tr.getOrigin()[1],tr.getOrigin()[2]};
b3Quaternion born = tr.getRotation();
float orn[4] = {born[0],born[1],born[2],born[3]};
sIsPressed=-1;
printf("device released: %d",unDevice);
sExample->vrControllerButtonCallback(unDevice,1,0,pos, orn);
}
}
}
}
m_rbShowTrackedDevice[ unDevice ] = state.ulButtonPressed == 0; m_rbShowTrackedDevice[ unDevice ] = state.ulButtonPressed == 0;
} }
} }
@@ -1480,7 +1551,7 @@ void CMainApplication::RenderStereoTargets()
rotYtoZ.rotateX(-90); rotYtoZ.rotateX(-90);
} }
RenderScene( vr::Eye_Left );
// Left Eye // Left Eye
{ {
@@ -1527,7 +1598,7 @@ void CMainApplication::RenderStereoTargets()
m_app->m_window->startRendering(); m_app->m_window->startRendering();
RenderScene( vr::Eye_Left );
@@ -1560,7 +1631,7 @@ void CMainApplication::RenderStereoTargets()
// Right Eye // Right Eye
RenderScene( vr::Eye_Right );
{ {
Matrix4 viewMatRight = m_mat4eyePosRight * m_mat4HMDPose * rotYtoZ; Matrix4 viewMatRight = m_mat4eyePosRight * m_mat4HMDPose * rotYtoZ;
@@ -1573,7 +1644,7 @@ void CMainApplication::RenderStereoTargets()
m_app->m_window->startRendering(); m_app->m_window->startRendering();
RenderScene( vr::Eye_Right );
m_app->m_instancingRenderer->setRenderFrameBuffer((unsigned int)rightEyeDesc.m_nRenderFramebufferId); m_app->m_instancingRenderer->setRenderFrameBuffer((unsigned int)rightEyeDesc.m_nRenderFramebufferId);
//m_app->m_renderer->renderScene(); //m_app->m_renderer->renderScene();

View File

@@ -33,8 +33,10 @@ int b3ResourcePath::getExePath(char* path, int maxPathLenInBytes)
#else #else
#ifdef _WIN32 #ifdef _WIN32
//https://msdn.microsoft.com/en-us/library/windows/desktop/ms683197(v=vs.85).aspx //https://msdn.microsoft.com/en-us/library/windows/desktop/ms683197(v=vs.85).aspx
HMODULE hModule = GetModuleHandle(NULL); HMODULE hModule = GetModuleHandle(NULL);
numBytes = GetModuleFileName(hModule, path, maxPathLenInBytes); numBytes = GetModuleFileNameA(hModule, path, maxPathLenInBytes);
#else #else
///http://stackoverflow.com/questions/933850/how-to-find-the-location-of-the-executable-in-c ///http://stackoverflow.com/questions/933850/how-to-find-the-location-of-the-executable-in-c
numBytes = (int)readlink("/proc/self/exe", path, maxPathLenInBytes-1); numBytes = (int)readlink("/proc/self/exe", path, maxPathLenInBytes-1);

View File

@@ -410,6 +410,41 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args)
} }
static PyObject *
pybullet_setRealTimeSimulation(PyObject* self, PyObject* args)
{
if (0 == sm)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
{
int enableRealTimeSimulation = 0;
int ret;
b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm);
b3SharedMemoryStatusHandle statusHandle;
if (!PyArg_ParseTuple(args, "i", &enableRealTimeSimulation))
{
PyErr_SetString(SpamError, "setRealTimeSimulation expected a single value (integer).");
return NULL;
}
ret = b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
//ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED);
}
Py_INCREF(Py_None);
return Py_None;
}
// Set the gravity of the world with (x, y, z) arguments // Set the gravity of the world with (x, y, z) arguments
static PyObject * static PyObject *
pybullet_setGravity(PyObject* self, PyObject* args) pybullet_setGravity(PyObject* self, PyObject* args)
@@ -1453,6 +1488,9 @@ static PyMethodDef SpamMethods[] = {
{"setTimeStep", pybullet_setTimeStep, METH_VARARGS, {"setTimeStep", pybullet_setTimeStep, METH_VARARGS,
"Set the amount of time to proceed at each call to stepSimulation. (unit is seconds, typically range is 0.01 or 0.001)"}, "Set the amount of time to proceed at each call to stepSimulation. (unit is seconds, typically range is 0.01 or 0.001)"},
{ "setRealTimeSimulation", pybullet_setRealTimeSimulation, METH_VARARGS,
"Enable or disable real time simulation (using the real time clock, RTC) in the physics server. Expects one integer argument, 0 or 1" },
{"loadURDF", pybullet_loadURDF, METH_VARARGS, {"loadURDF", pybullet_loadURDF, METH_VARARGS,
"Create a multibody by loading a URDF file."}, "Create a multibody by loading a URDF file."},

View File

@@ -636,10 +636,10 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev
FILETIME modtimeBinary; FILETIME modtimeBinary;
CreateDirectory(sCachedBinaryPath,0); CreateDirectoryA(sCachedBinaryPath,0);
{ {
HANDLE binaryFileHandle = CreateFile(binaryFileName,GENERIC_READ,0,0,OPEN_EXISTING,FILE_ATTRIBUTE_NORMAL,0); HANDLE binaryFileHandle = CreateFileA(binaryFileName,GENERIC_READ,0,0,OPEN_EXISTING,FILE_ATTRIBUTE_NORMAL,0);
if (binaryFileHandle ==INVALID_HANDLE_VALUE) if (binaryFileHandle ==INVALID_HANDLE_VALUE)
{ {
DWORD errorCode; DWORD errorCode;
@@ -677,7 +677,7 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev
if (binaryFileValid) if (binaryFileValid)
{ {
HANDLE srcFileHandle = CreateFile(clFileNameForCaching,GENERIC_READ,0,0,OPEN_EXISTING,FILE_ATTRIBUTE_NORMAL,0); HANDLE srcFileHandle = CreateFileA(clFileNameForCaching,GENERIC_READ,0,0,OPEN_EXISTING,FILE_ATTRIBUTE_NORMAL,0);
if (srcFileHandle==INVALID_HANDLE_VALUE) if (srcFileHandle==INVALID_HANDLE_VALUE)
{ {
@@ -686,7 +686,7 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev
{ {
char relativeFileName[1024]; char relativeFileName[1024];
sprintf(relativeFileName,"%s%s",prefix[i],clFileNameForCaching); sprintf(relativeFileName,"%s%s",prefix[i],clFileNameForCaching);
srcFileHandle = CreateFile(relativeFileName,GENERIC_READ,0,0,OPEN_EXISTING,FILE_ATTRIBUTE_NORMAL,0); srcFileHandle = CreateFileA(relativeFileName,GENERIC_READ,0,0,OPEN_EXISTING,FILE_ATTRIBUTE_NORMAL,0);
} }
} }

View File

@@ -26,14 +26,16 @@ class btDispatcher;
#include "btCollisionCreateFunc.h" #include "btCollisionCreateFunc.h"
///For each triangle in the concave mesh that overlaps with the AABB of a convex (m_convexProxy), processTriangle is called. ///For each triangle in the concave mesh that overlaps with the AABB of a convex (m_convexProxy), processTriangle is called.
class btConvexTriangleCallback : public btTriangleCallback ATTRIBUTE_ALIGNED16(class) btConvexTriangleCallback : public btTriangleCallback
{ {
const btCollisionObjectWrapper* m_convexBodyWrap;
const btCollisionObjectWrapper* m_triBodyWrap;
btVector3 m_aabbMin; btVector3 m_aabbMin;
btVector3 m_aabbMax ; btVector3 m_aabbMax ;
const btCollisionObjectWrapper* m_convexBodyWrap;
const btCollisionObjectWrapper* m_triBodyWrap;
btManifoldResult* m_resultOut; btManifoldResult* m_resultOut;
btDispatcher* m_dispatcher; btDispatcher* m_dispatcher;
@@ -41,6 +43,8 @@ class btConvexTriangleCallback : public btTriangleCallback
btScalar m_collisionMarginTriangle; btScalar m_collisionMarginTriangle;
public: public:
BT_DECLARE_ALIGNED_ALLOCATOR();
int m_triangleCount; int m_triangleCount;
btPersistentManifold* m_manifoldPtr; btPersistentManifold* m_manifoldPtr;
@@ -75,17 +79,19 @@ int m_triangleCount;
/// btConvexConcaveCollisionAlgorithm supports collision between convex shapes and (concave) trianges meshes. /// btConvexConcaveCollisionAlgorithm supports collision between convex shapes and (concave) trianges meshes.
class btConvexConcaveCollisionAlgorithm : public btActivatingCollisionAlgorithm ATTRIBUTE_ALIGNED16(class) btConvexConcaveCollisionAlgorithm : public btActivatingCollisionAlgorithm
{ {
bool m_isSwapped;
btConvexTriangleCallback m_btConvexTriangleCallback; btConvexTriangleCallback m_btConvexTriangleCallback;
bool m_isSwapped;
public: public:
BT_DECLARE_ALIGNED_ALLOCATOR();
btConvexConcaveCollisionAlgorithm( const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,bool isSwapped); btConvexConcaveCollisionAlgorithm( const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,bool isSwapped);
virtual ~btConvexConcaveCollisionAlgorithm(); virtual ~btConvexConcaveCollisionAlgorithm();

View File

@@ -123,6 +123,7 @@ btDefaultCollisionConfiguration::btDefaultCollisionConfiguration(const btDefault
m_persistentManifoldPool = new (mem) btPoolAllocator(sizeof(btPersistentManifold),constructionInfo.m_defaultMaxPersistentManifoldPoolSize); m_persistentManifoldPool = new (mem) btPoolAllocator(sizeof(btPersistentManifold),constructionInfo.m_defaultMaxPersistentManifoldPoolSize);
} }
collisionAlgorithmMaxElementSize = (collisionAlgorithmMaxElementSize+16)&0xffffffffffff0;
if (constructionInfo.m_collisionAlgorithmPool) if (constructionInfo.m_collisionAlgorithmPool)
{ {
m_ownsCollisionAlgorithmPool = false; m_ownsCollisionAlgorithmPool = false;