Merge remote-tracking branch 'bp/master'

This commit is contained in:
Erwin Coumans
2017-10-29 12:28:00 -07:00
9 changed files with 213 additions and 96 deletions

View File

@@ -301,8 +301,12 @@ IF (APPLE)
ENDIF()
OPTION(BUILD_BULLET3 "Set when you want to build Bullet 3" ON)
# Optional Python configuration
# builds pybullet automatically if all the requirements are met
# Will not probe environment for Python configuration (which can abort the
# build process) unless you explicitly turn on BUILD_PYBULLET.
OPTION(BUILD_PYBULLET "Set when you want to build pybullet (Python bindings for Bullet)" OFF)
IF(BUILD_PYBULLET)
SET(PYTHON_VERSION_PYBULLET "" CACHE STRING "Python version pybullet will use.")
SET(Python_ADDITIONAL_VERSIONS 3 3.6 3.5 3.4 3.3 3.2 3.1 3.0 2.7 2.7.12 2.7.10 2.7.3 )
SET_PROPERTY(CACHE PYTHON_VERSION_PYBULLET PROPERTY STRINGS ${Python_ADDITIONAL_VERSIONS})
@@ -314,12 +318,9 @@ ENDIF(EXACT_PYTHON_VERSION)
# first find the python interpreter
FIND_PACKAGE(PythonInterp ${PYTHON_VERSION_PYBULLET} ${EXACT_PYTHON_VERSION_FLAG})
# python library should exactly match that of the interpreter
# the following can result in fatal error if you don't have the right python configuration
FIND_PACKAGE(PythonLibs ${PYTHON_VERSION_STRING} EXACT)
SET(DEFAULT_BUILD_PYBULLET OFF)
IF(PYTHONLIBS_FOUND)
SET(DEFAULT_BUILD_PYBULLET ON)
ENDIF(PYTHONLIBS_FOUND)
OPTION(BUILD_PYBULLET "Set when you want to build pybullet (Python bindings for Bullet)" ${DEFAULT_BUILD_PYBULLET})
ENDIF(BUILD_PYBULLET)
OPTION(BUILD_ENET "Set when you want to build apps with enet UDP networking support" ON)
OPTION(BUILD_CLSOCKET "Set when you want to build apps with enet TCP networking support" ON)

View File

@@ -63,7 +63,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0.0455 0"/>
<geometry>
<box size=".307 0.009 .050"/>
<box size=".356 0.009 .050"/>
</geometry>
<material name="grey">
<color rgba="0.65 0.65 0.75 1"/>
@@ -72,12 +72,49 @@
<visual>
<origin rpy="0 0 0" xyz="0 -0.0455 0"/>
<geometry>
<box size=".307 0.009 .050"/>
<box size=".356 0.009 .050"/>
</geometry>
<material name="grey">
<color rgba="0.65 0.65 0.75 1"/>
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="0.212 -0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
<material name="grey">
<color rgba="0.65 0.65 0.75 1"/>
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="0.212 0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
<material name="grey">
<color rgba="0.65 0.65 0.75 1"/>
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="-0.212 -0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
<material name="grey">
<color rgba="0.65 0.65 0.75 1"/>
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="-0.212 0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
<material name="grey">
<color rgba="0.65 0.65 0.75 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0.1165 0"/>
@@ -88,18 +125,43 @@
<collision>
<origin rpy="0 0 0" xyz="0 0.0455 0"/>
<geometry>
<box size=".307 0.009 .050"/>
<box size=".356 0.009 .050"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0 -0.0455 0"/>
<geometry>
<box size=".307 0.009 .050"/>
<box size=".356 0.009 .050"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.212 -0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.212 0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="-0.212 -0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="-0.212 0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
</collision>
<inertial>
<mass value=".72277"/>
<inertia ixx="0.00125923" ixy="0.0" ixz="0.0" iyy="0.00346491" iyz="0.0" izz="0.00420849"/>
<mass value="1.3668"/>
<inertia ixx="0.0038077" ixy="0.0" ixz="0.0" iyy="0.0328502" iyz="0.0" izz="0.03575585"/>
</inertial>
</link>
@@ -125,7 +187,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0.0455 0"/>
<geometry>
<box size=".307 0.009 .050"/>
<box size=".356 0.009 .050"/>
</geometry>
<material name="grey">
<color rgba="0.65 0.65 0.75 1"/>
@@ -134,12 +196,49 @@
<visual>
<origin rpy="0 0 0" xyz="0 -0.0455 0"/>
<geometry>
<box size=".307 0.009 .050"/>
<box size=".356 0.009 .050"/>
</geometry>
<material name="grey">
<color rgba="0.65 0.65 0.75 1"/>
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="0.212 -0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
<material name="grey">
<color rgba="0.65 0.65 0.75 1"/>
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="0.212 0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
<material name="grey">
<color rgba="0.65 0.65 0.75 1"/>
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="-0.212 -0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
<material name="grey">
<color rgba="0.65 0.65 0.75 1"/>
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="-0.212 0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
<material name="grey">
<color rgba="0.65 0.65 0.75 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0.1165 0"/>
@@ -150,18 +249,43 @@
<collision>
<origin rpy="0 0 0" xyz="0 0.0455 0"/>
<geometry>
<box size=".307 0.009 .050"/>
<box size=".356 0.009 .050"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0 -0.0455 0"/>
<geometry>
<box size=".307 0.009 .050"/>
<box size=".356 0.009 .050"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.212 -0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.212 0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="-0.212 -0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="-0.212 0.05915 0"/>
<geometry>
<box size=".068 0.0373 .060"/>
</geometry>
</collision>
<inertial>
<mass value=".72277"/>
<inertia ixx="0.00125923" ixy="0.0" ixz="0.0" iyy="0.00346491" iyz="0.0" izz="0.00420849"/>
<mass value="1.3668"/>
<inertia ixx="0.0038077" ixy="0.0" ixz="0.0" iyy="0.0328502" iyz="0.0" izz="0.03575585"/>
</inertial>
</link>
@@ -185,19 +309,19 @@
</visual>
<collision>
<geometry>
<cylinder length="0.059" radius="0.05268"/>
<cylinder length="0.0165" radius="0.0425"/>
</geometry>
</collision>
<inertial>
<mass value="0.402"/>
<inertia ixx="0.0003378" ixy="0.0" ixz="0.0" iyy="0.0012213" iyz="0.0" izz="0.001058"/>
<mass value="0.241"/>
<inertia ixx="0.00011397" ixy="0.0" ixz="0.0" iyy="0.00011397" iyz="0.0" izz="0.00021765"/>
</inertial>
</link>
<joint name="motor_front_rightR_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="chassis_right"/>
<child link="motor_front_rightR_link"/>
<origin rpy="1.57075 0 0" xyz="0.20268 -0.0455 0"/>
<origin rpy="1.57075 0 0" xyz="0.20268 -0.03275 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -213,19 +337,19 @@
</visual>
<collision>
<geometry>
<cylinder length="0.059" radius="0.05268"/>
<cylinder length="0.0165" radius="0.0425"/>
</geometry>
</collision>
<inertial>
<mass value="0.402"/>
<inertia ixx="0.0003378" ixy="0.0" ixz="0.0" iyy="0.0012213" iyz="0.0" izz="0.001058"/>
<mass value="0.241"/>
<inertia ixx="0.00011397" ixy="0.0" ixz="0.0" iyy="0.00011397" iyz="0.0" izz="0.00021765"/>
</inertial>
</link>
<joint name="motor_front_rightL_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="chassis_right"/>
<child link="motor_front_rightL_link"/>
<origin rpy="1.57075 0 3.141592" xyz="0.20268 0.0455 0"/>
<origin rpy="1.57075 0 3.141592" xyz="0.20268 0.03275 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -241,19 +365,19 @@
</visual>
<collision>
<geometry>
<cylinder length="0.059" radius="0.05268"/>
<cylinder length="0.0165" radius="0.0425"/>
</geometry>
</collision>
<inertial>
<mass value="0.402"/>
<inertia ixx="0.0003378" ixy="0.0" ixz="0.0" iyy="0.0012213" iyz="0.0" izz="0.001058"/>
<mass value="0.241"/>
<inertia ixx="0.00011397" ixy="0.0" ixz="0.0" iyy="0.00011397" iyz="0.0" izz="0.00021765"/>
</inertial>
</link>
<joint name="motor_front_leftL_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="chassis_left"/>
<child link="motor_front_leftL_link"/>
<origin rpy="1.57075 0 3.141592" xyz="0.20268 0.0455 0"/>
<origin rpy="1.57075 0 3.141592" xyz="0.20268 0.03275 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -269,19 +393,19 @@
</visual>
<collision>
<geometry>
<cylinder length="0.059" radius="0.05268"/>
<cylinder length="0.0165" radius="0.0425"/>
</geometry>
</collision>
<inertial>
<mass value="0.402"/>
<inertia ixx="0.0003378" ixy="0.0" ixz="0.0" iyy="0.0012213" iyz="0.0" izz="0.001058"/>
<mass value="0.241"/>
<inertia ixx="0.00011397" ixy="0.0" ixz="0.0" iyy="0.00011397" iyz="0.0" izz="0.00021765"/>
</inertial>
</link>
<joint name="motor_front_leftR_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="chassis_left"/>
<child link="motor_front_leftR_link"/>
<origin rpy="1.57075 0 0" xyz="0.20268 -0.0455 0"/>
<origin rpy="1.57075 0 0" xyz="0.20268 -0.03275 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -297,19 +421,19 @@
</visual>
<collision>
<geometry>
<cylinder length="0.059" radius="0.05268"/>
<cylinder length="0.0165" radius="0.0425"/>
</geometry>
</collision>
<inertial>
<mass value="0.402"/>
<inertia ixx="0.0003378" ixy="0.0" ixz="0.0" iyy="0.0012213" iyz="0.0" izz="0.001058"/>
<mass value="0.241"/>
<inertia ixx="0.00011397" ixy="0.0" ixz="0.0" iyy="0.00011397" iyz="0.0" izz="0.00021765"/>
</inertial>
</link>
<joint name="motor_back_rightR_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="chassis_right"/>
<child link="motor_back_rightR_link"/>
<origin rpy="1.57075 0 0" xyz="-0.20268 -0.0455 0"/>
<origin rpy="1.57075 0 0" xyz="-0.20268 -0.03275 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -325,19 +449,19 @@
</visual>
<collision>
<geometry>
<cylinder length="0.059" radius="0.05268"/>
<cylinder length="0.0165" radius="0.0425"/>
</geometry>
</collision>
<inertial>
<mass value="0.402"/>
<inertia ixx="0.0003378" ixy="0.0" ixz="0.0" iyy="0.0012213" iyz="0.0" izz="0.001058"/>
<mass value="0.241"/>
<inertia ixx="0.00011397" ixy="0.0" ixz="0.0" iyy="0.00011397" iyz="0.0" izz="0.00021765"/>
</inertial>
</link>
<joint name="motor_back_rightL_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="chassis_right"/>
<child link="motor_back_rightL_link"/>
<origin rpy="1.57075 0 3.141592" xyz="-0.20268 0.0455 0"/>
<origin rpy="1.57075 0 3.141592" xyz="-0.20268 0.03275 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -353,19 +477,19 @@
</visual>
<collision>
<geometry>
<cylinder length="0.059" radius="0.05268"/>
<cylinder length="0.0165" radius="0.0425"/>
</geometry>
</collision>
<inertial>
<mass value="0.402"/>
<inertia ixx="0.0003378" ixy="0.0" ixz="0.0" iyy="0.0012213" iyz="0.0" izz="0.001058"/>
<mass value="0.241"/>
<inertia ixx="0.00011397" ixy="0.0" ixz="0.0" iyy="0.00011397" iyz="0.0" izz="0.00021765"/>
</inertial>
</link>
<joint name="motor_back_leftL_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="chassis_left"/>
<child link="motor_back_leftL_link"/>
<origin rpy="1.57075 0 3.141592" xyz="-0.20268 0.0455 0"/>
<origin rpy="1.57075 0 3.141592" xyz="-0.20268 0.03275 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -381,19 +505,19 @@
</visual>
<collision>
<geometry>
<cylinder length="0.059" radius="0.05268"/>
<cylinder length="0.0165" radius="0.0425"/>
</geometry>
</collision>
<inertial>
<mass value="0.402"/>
<inertia ixx="0.0003378" ixy="0.0" ixz="0.0" iyy="0.0012213" iyz="0.0" izz="0.001058"/>
<mass value="0.241"/>
<inertia ixx="0.00011397" ixy="0.0" ixz="0.0" iyy="0.00011397" iyz="0.0" izz="0.00021765"/>
</inertial>
</link>
<joint name="motor_back_leftR_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="chassis_left"/>
<child link="motor_back_leftR_link"/>
<origin rpy="1.57075 0 0" xyz="-0.20268 -0.0455 0"/>
<origin rpy="1.57075 0 0" xyz="-0.20268 -0.03275 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -423,7 +547,7 @@
<axis xyz="0 0 1"/>
<parent link="motor_front_rightR_link"/>
<child link="upper_leg_front_rightR_link"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.030"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.01725"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -491,7 +615,7 @@
<axis xyz="0 0 1"/>
<parent link="motor_front_rightL_link"/>
<child link="upper_leg_front_rightL_link"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.030"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.01725"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -560,7 +684,7 @@
<axis xyz="0 0 1"/>
<parent link="motor_front_leftR_link"/>
<child link="upper_leg_front_leftR_link"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.030"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.01725"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -628,7 +752,7 @@
<axis xyz="0 0 1"/>
<parent link="motor_front_leftL_link"/>
<child link="upper_leg_front_leftL_link"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.030"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.01725"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -697,7 +821,7 @@
<axis xyz="0 0 1"/>
<parent link="motor_back_rightR_link"/>
<child link="upper_leg_back_rightR_link"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.030"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.01725"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -765,7 +889,7 @@
<axis xyz="0 0 1"/>
<parent link="motor_back_rightL_link"/>
<child link="upper_leg_back_rightL_link"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.030"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.01725"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -834,7 +958,7 @@
<axis xyz="0 0 1"/>
<parent link="motor_back_leftR_link"/>
<child link="upper_leg_back_leftR_link"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.030"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.01725"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
@@ -902,7 +1026,7 @@
<axis xyz="0 0 1"/>
<parent link="motor_back_leftL_link"/>
<child link="upper_leg_back_leftL_link"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.030"/>
<origin rpy="-1.57075 0 0" xyz="0.0 0.045 -0.01725"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>

View File

@@ -439,15 +439,12 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam)
void Win32Window::setWindowTitle(const char* titleChar)
{
wchar_t windowTitle[1024];
swprintf(windowTitle, 1024, L"%hs", titleChar);
#ifdef _WIN64
SetWindowTextW(m_data->m_hWnd, windowTitle);
SetWindowText(m_data->m_hWnd, titleChar);
#else
DWORD dwResult;
SendMessageTimeoutW(m_data->m_hWnd, WM_SETTEXT, 0,
reinterpret_cast<LPARAM>(windowTitle),
SendMessageTimeout(m_data->m_hWnd, WM_SETTEXT, 0,
reinterpret_cast<LPARAM>(titleChar),
SMTO_ABORTIFHUNG, 2000, &dwResult);
#endif
}

View File

@@ -15,7 +15,7 @@ IF(NOT WIN32 AND NOT APPLE)
ADD_DEFINITIONS("-DDYNAMIC_LOAD_X11_FUNCTIONS=1")
ENDIF()
ADD_DEFINITIONS( -DGLEW_STATIC -DGWEN_COMPILE_STATIC -D_HAS_EXCEPTIONS=0 -D_STATIC_CPPLIB )
ADD_DEFINITIONS( -DGLEW_STATIC -DGWEN_COMPILE_STATIC -D_HAS_EXCEPTIONS=0 )
FILE(GLOB gwen_SRCS "*.cpp" "Controls/*.cpp" "Controls/Dialog/*.cpp" "Controls/Dialogs/*.cpp" "Controls/Layout/*.cpp" "Controls/Property/*.cpp" "Input/*.cpp" "Platforms/*.cpp" "Renderers/*.cpp" "Skins/*.cpp")
FILE(GLOB gwen_HDRS "*.h" "Controls/*.h" "Controls/Dialog/*.h" "Controls/Dialogs/*.h" "Controls/Layout/*.h" "Controls/Property/*.h" "Input/*.h" "Platforms/*.h" "Renderers/*.h" "Skins/*.h")

View File

@@ -4,6 +4,7 @@
#define GWEN_MACROS_H
#include <stdlib.h>
#include <stdarg.h>
#include <stdio.h> // vsnprintf
#if !defined(__APPLE__) && !defined(__OpenBSD__) && !defined(__FreeBSD__)
#include <malloc.h>
#else
@@ -17,7 +18,7 @@
#define GwenUtil_Max( a, b ) ( ( (a) > (b) ) ? (a) : (b) )
#define GwenUtil_VSWPrintFSafeSized( _DstBuf_ARRAY_, _Format, _ArgList ) GwenUtil_VSWPrintFSafe( _DstBuf_ARRAY_, sizeof( _DstBuf_ARRAY_ ) / sizeof( wchar_t ), _Format, _ArgList )
#ifdef _WIN32
#ifdef _MSC_VER
#ifndef NOMINMAX
#define NOMINMAX
@@ -40,10 +41,15 @@
#define GwenUtil_OutputDebugWideString( lpOutputString ) //wprintf( lpOutputString )
#define GwenUtil_WideStringToFloat( _Str ) wcstof(_Str, NULL)
#elif defined(__linux__) || defined(__OpenBSD__)
#elif defined(__linux__) || defined( __GNUC__ )
#define GwenUtil_VSNPrintFSafe( _DstBuf, _DstSize, _MaxCount, _Format, _ArgList ) vsnprintf( _DstBuf, _DstSize, _Format, _ArgList )
#ifdef _WIN32
#define GwenUtil_VSWPrintFSafe( _DstBuf, _SizeInWords, _Format, _ArgList ) vsnwprintf( _DstBuf, _SizeInWords, _Format, _ArgList )
#else
#define GwenUtil_VSWPrintFSafe( _DstBuf, _SizeInWords, _Format, _ArgList ) vswprintf( _DstBuf, _SizeInWords, _Format, _ArgList )
#endif
#define GwenUtil_OutputDebugCharString( lpOutputString ) //printf( lpOutputString )
#define GwenUtil_OutputDebugWideString( lpOutputString ) //wprintf( lpOutputString )
#define GwenUtil_WideStringToFloat( _Str ) wcstof(_Str, NULL)

View File

@@ -36,7 +36,7 @@ struct b3FileUtils
for (int i=0;!f && i<numPrefixes;i++)
{
#ifdef _WIN32
#ifdef _MSC_VER
sprintf_s(relativeFileName,maxRelativeFileNameMaxLen,"%s%s",prefix[i],orgFileName);
#else
sprintf(relativeFileName,"%s%s",prefix[i],orgFileName);

View File

@@ -619,7 +619,7 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev
strippedName = strip2(clFileNameForCaching,"\\");
strippedName = strip2(strippedName,"/");
#ifdef _MSVC_VER
#ifdef _MSC_VER
sprintf_s(binaryFileName,B3_MAX_STRING_LENGTH,"%s/%s.%s.%s.bin",sCachedBinaryPath,strippedName, deviceName,driverVersion );
#else
sprintf(binaryFileName,"%s/%s.%s.%s.bin",sCachedBinaryPath,strippedName, deviceName,driverVersion );

View File

@@ -396,32 +396,24 @@ void btCompoundCompoundCollisionAlgorithm::processCollision (const btCollisionOb
btCollisionAlgorithm* algo = (btCollisionAlgorithm*)pairs[i].m_userPointer;
{
btTransform orgTrans0;
const btCollisionShape* childShape0 = 0;
btTransform newChildWorldTrans0;
btTransform orgInterpolationTrans0;
childShape0 = compoundShape0->getChildShape(pairs[i].m_indexA);
orgTrans0 = col0ObjWrap->getWorldTransform();
orgInterpolationTrans0 = col0ObjWrap->getWorldTransform();
const btTransform& childTrans0 = compoundShape0->getChildTransform(pairs[i].m_indexA);
newChildWorldTrans0 = orgTrans0*childTrans0 ;
newChildWorldTrans0 = col0ObjWrap->getWorldTransform()*childTrans0 ;
childShape0->getAabb(newChildWorldTrans0,aabbMin0,aabbMax0);
}
btVector3 thresholdVec(resultOut->m_closestPointDistanceThreshold, resultOut->m_closestPointDistanceThreshold, resultOut->m_closestPointDistanceThreshold);
aabbMin0 -= thresholdVec;
aabbMax0 += thresholdVec;
{
btTransform orgInterpolationTrans1;
const btCollisionShape* childShape1 = 0;
btTransform orgTrans1;
btTransform newChildWorldTrans1;
childShape1 = compoundShape1->getChildShape(pairs[i].m_indexB);
orgTrans1 = col1ObjWrap->getWorldTransform();
orgInterpolationTrans1 = col1ObjWrap->getWorldTransform();
const btTransform& childTrans1 = compoundShape1->getChildTransform(pairs[i].m_indexB);
newChildWorldTrans1 = orgTrans1*childTrans1 ;
newChildWorldTrans1 = col1ObjWrap->getWorldTransform()*childTrans1 ;
childShape1->getAabb(newChildWorldTrans1,aabbMin1,aabbMax1);
}

View File

@@ -1425,9 +1425,6 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
fb->m_appliedTorqueBodyB.setZero();
}
if (constraints[i]->isEnabled())
{
}
if (constraints[i]->isEnabled())
{
constraints[i]->getInfo1(&info1);