This commit is contained in:
erwincoumans
2019-06-01 07:29:09 -07:00
39 changed files with 135069 additions and 9159 deletions

View File

@@ -9,9 +9,9 @@
#include "../../CommonInterfaces/CommonFileIOInterface.h"
#include "../ImportURDFDemo/UrdfFindMeshFile.h"
#include <string>
#include "../../Utils/b3ResourcePath.h"
#include <iostream>
#include <fstream>
#include "../../Utils/b3ResourcePath.h"
#include "../ImportURDFDemo/URDF2Bullet.h"
#include "../ImportURDFDemo/UrdfParser.h"
#include "../ImportURDFDemo/urdfStringSplit.h"
@@ -1453,17 +1453,15 @@ bool BulletMJCFImporter::loadMJCF(const char* fileName, MJCFErrorLogger* logger,
}
else
{
int maxPathLen = 1024;
fu.extractPath(relativeFileName, m_data->m_pathPrefix, maxPathLen);
//read file
int fileId = m_data->m_fileIO->fileOpen(relativeFileName,"r");
std::fstream xml_file(relativeFileName, std::fstream::in);
while (xml_file.good())
char destBuffer[8192];
while (m_data->m_fileIO->readLine(fileId, destBuffer, 8192))
{
std::string line;
std::getline(xml_file, line);
xml_string += (line + "\n");
xml_string += (std::string(destBuffer) + "\n");
}
xml_file.close();
m_data->m_fileIO->fileClose(fileId);
if (parseMJCFString(xml_string.c_str(), logger))
{

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,480 @@
<?xml version="1.0" ?>
<robot name="mini_cheetah" xmlns:xacro="http://ros.org/wiki/xacro">
<link name="body">
<inertial>
<mass value="3.3"/>
<origin xyz="0.0 0.0 0.0"/>
<inertia ixx="0.011253" ixy="0" ixz="0" iyy="0.362030" iyz="0" izz="0.042673"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_body.obj"/>
</geometry>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_body.obj"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
</link>
<!--!!!!!!!!!!!! Front Right Leg !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!-->
<joint name="torso_to_abduct_fr_j" type="continuous">
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="0.19 -0.049 0.0"/>
<parent link="body"/>
<child link="abduct_fr"/>
</joint>
<link name="abduct_fr">
<inertial>
<mass value="0.54"/>
<origin xyz="0.0 0.036 0."/>
<inertia ixx="0.000381" ixy="0.000058" ixz="0.00000045"
iyy="0.000560" iyz="0.00000095" izz="0.000444"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_abad.obj"/>
</geometry>
<origin rpy="3.141592 0.0 1.5708" xyz="-0.055 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_abad.obj"/>
</geometry>
<origin rpy="3.141592 0 1.5708" xyz="-0.055 0 0"/>
</collision>
</link>
<joint name="abduct_fr_to_thigh_fr_j" type="continuous">
<axis xyz="0 -1 0"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 -0.062 0.00"/>
<parent link="abduct_fr"/>
<child link="thigh_fr"/>
</joint>
<link name="thigh_fr">
<inertial>
<mass value="0.634"/>
<origin xyz="0.0 0.016 -0.02"/>
<inertia ixx="0.001983" ixy="0.000245" ixz="0.000013"
iyy="0.002103" iyz="0.0000015" izz="0.000408"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_upper_link.obj"/>
</geometry>
<origin rpy="0.0 -1.5708 0.0" xyz="0.0 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_upper_link.obj"/>
</geometry>
<origin rpy="0 -1.5708 0" xyz="0 0 0"/>
</collision>
</link>
<joint name="thigh_fr_to_knee_fr_j" type="continuous">
<axis xyz="0 -1 0"/>
<origin rpy="0.0 0 0.0" xyz="0.0 0.0 -0.209"/>
<parent link="thigh_fr"/>
<child link="shank_fr"/>
</joint>
<link name="shank_fr">
<inertial>
<mass value="0.064"/>
<origin xyz="0.0 0.0 -0.209"/>
<inertia ixx="0.000245" ixy="0" ixz="0.0" iyy="0.000248" iyz="0" izz="0.000006"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_lower_link.obj"/>
</geometry>
<origin rpy="0.0 3.141592 0.0" xyz="0.0 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_lower_link.obj"/>
</geometry>
<origin rpy="0 3.141592 0" xyz="0 0 0"/>
</collision>
</link>
<link name="toe_fr">
<contact>
<friction_anchor/>
<stiffness value="30000.0"/>
<damping value="1000.0"/>
<spinning_friction value="0.3"/>
<lateral_friction value="3.0"/>
</contact>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.015"/>
</geometry>
<material name="darkgray"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.015"/>
</geometry>
</collision>
<inertial>
<mass value="0.15"/>
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
</inertial>
</link>
<joint name="toe_fr_joint" type="fixed">
<parent link="shank_fr"/>
<child link="toe_fr"/>
<origin xyz="0 0 -0.18"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!--!!!!!!!!!!!! Front Left Leg !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!-->
<joint name="torso_to_abduct_fl_j" type="continuous">
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="0.19 0.049 0.0"/>
<parent link="body"/>
<child link="abduct_fl"/>
</joint>
<link name="abduct_fl">
<inertial>
<mass value="0.54"/>
<origin xyz="0.0 0.036 0."/>
<inertia ixx="0.000381" ixy="0.000058" ixz="0.00000045"
iyy="0.000560" iyz="0.00000095" izz="0.000444"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_abad.obj"/>
</geometry>
<origin rpy="0. 0. -1.5708" xyz="-0.055 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_abad.obj"/>
</geometry>
<origin rpy="0 0 -1.5708" xyz="-0.055 0 0"/>
</collision>
</link>
<joint name="abduct_fl_to_thigh_fl_j" type="continuous">
<axis xyz="0 -1 0"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.062 0.00"/>
<parent link="abduct_fl"/>
<child link="thigh_fl"/>
</joint>
<link name="thigh_fl">
<inertial>
<mass value="0.634"/>
<origin xyz="0.0 0.016 -0.02"/>
<inertia ixx="0.001983" ixy="0.000245" ixz="0.000013"
iyy="0.002103" iyz="0.0000015" izz="0.000408"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_upper_link.obj"/>
</geometry>
<origin rpy="0.0 -1.5708 0.0" xyz="0.0 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_upper_link.obj"/>
</geometry>
<origin rpy="0 -1.5708 0" xyz="0 0 0"/>
</collision>
</link>
<joint name="thigh_fl_to_knee_fl_j" type="continuous">
<axis xyz="0 -1 0"/>
<origin rpy="0.0 0 0.0" xyz="0.0 0.0 -0.209"/>
<parent link="thigh_fl"/>
<child link="shank_fl"/>
</joint>
<link name="shank_fl">
<inertial>
<mass value="0.064"/>
<origin xyz="0.0 0.0 -0.209"/>
<inertia ixx="0.000245" ixy="0" ixz="0.0" iyy="0.000248" iyz="0" izz="0.000006"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_lower_link.obj"/>
</geometry>
<origin rpy="0.0 3.141592 0.0" xyz="0.0 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_lower_link.obj"/>
</geometry>
<origin rpy="0 3.141592 0" xyz="0 0 0"/>
</collision>
</link>
<link name="toe_fl">
<contact>
<friction_anchor/>
<stiffness value="30000.0"/>
<damping value="1000.0"/>
<spinning_friction value="0.3"/>
<lateral_friction value="3.0"/>
</contact>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.015"/>
</geometry>
<material name="darkgray"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.015"/>
</geometry>
</collision>
<inertial>
<mass value="0.15"/>
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
</inertial>
</link>
<joint name="toe_fl_joint" type="fixed">
<parent link="shank_fl"/>
<child link="toe_fl"/>
<origin xyz="0 0 -0.18"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!--!!!!!!!!!!!! Hind Right Leg !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!-->
<joint name="torso_to_abduct_hr_j" type="continuous">
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="-0.19 -0.049 0.0"/>
<parent link="body"/>
<child link="abduct_hr"/>
</joint>
<link name="abduct_hr">
<inertial>
<mass value="0.54"/>
<origin xyz="0.0 0.036 0."/>
<inertia ixx="0.000381" ixy="0.000058" ixz="0.00000045"
iyy="0.000560" iyz="0.00000095" izz="0.000444"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_abad.obj"/>
</geometry>
<origin rpy="0.0 0.0 1.5708" xyz="0.055 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_abad.obj"/>
</geometry>
<origin rpy="0 0 1.5708" xyz="0.055 0 0"/>
</collision>
</link>
<joint name="abduct_hr_to_thigh_hr_j" type="continuous">
<axis xyz="0 -1 0"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 -0.062 0.00"/>
<parent link="abduct_hr"/>
<child link="thigh_hr"/>
</joint>
<link name="thigh_hr">
<inertial>
<mass value="0.634"/>
<origin xyz="0.0 0.016 -0.02"/>
<inertia ixx="0.001983" ixy="0.000245" ixz="0.000013"
iyy="0.002103" iyz="0.0000015" izz="0.000408"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_upper_link.obj"/>
</geometry>
<origin rpy="0.0 -1.5708 0.0" xyz="0.0 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_upper_link.obj"/>
</geometry>
<origin rpy="0 -1.5708 0" xyz="0 0 0"/>
</collision>
</link>
<joint name="thigh_hr_to_knee_hr_j" type="continuous">
<axis xyz="0 -1 0"/>
<origin rpy="0.0 0 0.0" xyz="0.0 0.0 -0.209"/>
<parent link="thigh_hr"/>
<child link="shank_hr"/>
</joint>
<link name="shank_hr">
<inertial>
<mass value="0.064"/>
<origin xyz="0.0 0.0 -0.209"/>
<inertia ixx="0.000245" ixy="0" ixz="0.0" iyy="0.000248" iyz="0" izz="0.000006"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_lower_link.obj"/>
</geometry>
<origin rpy="0.0 3.141592 0.0" xyz="0.0 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_lower_link.obj"/>
</geometry>
<origin rpy="0 3.141592 0" xyz="0 0 0"/>
</collision>
</link>
<link name="toe_hr">
<contact>
<friction_anchor/>
<stiffness value="30000.0"/>
<damping value="1000.0"/>
<spinning_friction value="0.3"/>
<lateral_friction value="3.0"/>
</contact>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.015"/>
</geometry>
<material name="darkgray"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.015"/>
</geometry>
</collision>
<inertial>
<mass value="0.15"/>
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
</inertial>
</link>
<joint name="toe_hr_joint" type="fixed">
<parent link="shank_hr"/>
<child link="toe_hr"/>
<origin xyz="0 0 -0.18"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!--!!!!!!!!!!!! Hind Left Leg !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!-->
<joint name="torso_to_abduct_hl_j" type="continuous">
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="-0.19 0.049 0.0"/>
<parent link="body"/>
<child link="abduct_hl"/>
</joint>
<link name="abduct_hl">
<inertial>
<mass value="0.54"/>
<origin xyz="0.0 0.036 0."/>
<inertia ixx="0.000381" ixy="0.000058" ixz="0.00000045"
iyy="0.000560" iyz="0.00000095" izz="0.000444"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_abad.obj"/>
</geometry>
<origin rpy="3.141592 0.0 -1.5708" xyz="0.055 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_abad.obj"/>
</geometry>
<origin rpy="3.141592 0 -1.5708" xyz="0.055 0 0"/>
</collision>
</link>
<joint name="abduct_hl_to_thigh_hl_j" type="continuous">
<axis xyz="0 -1 0"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.062 0.00"/>
<parent link="abduct_hl"/>
<child link="thigh_hl"/>
</joint>
<link name="thigh_hl">
<inertial>
<mass value="0.634"/>
<origin xyz="0.0 0.016 -0.02"/>
<inertia ixx="0.001983" ixy="0.000245" ixz="0.000013"
iyy="0.002103" iyz="0.0000015" izz="0.000408"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_upper_link.obj"/>
</geometry>
<origin rpy="0.0 -1.5708 0.0" xyz="0.0 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_upper_link.obj"/>
</geometry>
<origin rpy="0 -1.5708 0" xyz="0 0 0"/>
</collision>
</link>
<joint name="thigh_hl_to_knee_hl_j" type="continuous">
<axis xyz="0 -1 0"/>
<origin rpy="0.0 0 0.0" xyz="0.0 0.0 -0.209"/>
<parent link="thigh_hl"/>
<child link="shank_hl"/>
</joint>
<link name="shank_hl">
<inertial>
<mass value="0.064"/>
<origin xyz="0.0 0.0 -0.209"/>
<inertia ixx="0.000245" ixy="0" ixz="0.0" iyy="0.000248" iyz="0" izz="0.000006"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/mini_lower_link.obj"/>
</geometry>
<origin rpy="0.0 3.141592 0.0" xyz="0.0 0.0 0.0"/>
</visual>
<collision>
<geometry>
<mesh filename="meshes/mini_lower_link.obj"/>
</geometry>
<origin rpy="0 3.141592 0" xyz="0 0 0"/>
</collision>
</link>
<link name="toe_hl">
<contact>
<friction_anchor/>
<stiffness value="30000.0"/>
<damping value="1000.0"/>
<spinning_friction value="0.3"/>
<lateral_friction value="3.0"/>
</contact>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.015"/>
</geometry>
<material name="darkgray"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.015"/>
</geometry>
</collision>
<inertial>
<mass value="0.15"/>
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
</inertial>
</link>
<joint name="toe_hl_joint" type="fixed">
<parent link="shank_hl"/>
<child link="toe_hl"/>
<origin xyz="0 0 -0.18"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
</robot>

View File

@@ -0,0 +1,23 @@
import pybullet as p
import pybullet_data as pd
import time
p.connect(p.GUI)
p.setGravity(0,0,-9.8)
p.setAdditionalSearchPath(pd.getDataPath())
floor = p.loadURDF("plane.urdf")
startPos = [0,0,0.5]
robot = p.loadURDF("mini_cheetah/mini_cheetah.urdf",startPos)
numJoints = p.getNumJoints(robot)
p.changeVisualShape(robot,-1,rgbaColor=[1,1,1,1])
for j in range (numJoints):
p.changeVisualShape(robot,j,rgbaColor=[1,1,1,1])
force=200
pos=0
p.setJointMotorControl2(robot,j,p.POSITION_CONTROL,pos,force=force)
dt = 1./240.
p.setTimeStep(dt)
while (1):
p.stepSimulation()
time.sleep(dt)

View File

@@ -336,9 +336,10 @@ static PyObject* pybullet_stepSimulation(PyObject* self, PyObject* args, PyObjec
struct b3ForwardDynamicsAnalyticsArgs analyticsData;
int numIslands = 0;
int i;
PyObject* pyAnalyticsData = PyTuple_New(numIslands);
numIslands = b3GetStatusForwardDynamicsAnalyticsData(statusHandle, &analyticsData);
PyObject* pyAnalyticsData = PyTuple_New(numIslands);
for (i=0;i<numIslands;i++)
{
int numFields = 4;

View File

@@ -80,6 +80,7 @@ static DBVT_INLINE void deletenode(btDbvt* pdbvt,
static void recursedeletenode(btDbvt* pdbvt,
btDbvtNode* node)
{
if (node == 0) return;
if (!node->isleaf())
{
recursedeletenode(pdbvt, node->childs[0]);

View File

@@ -1,4 +1,4 @@
/*
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/

View File

@@ -311,9 +311,9 @@ void btGeneric6DofSpring2Constraint::calculateAngleInfo()
case RO_XYZ:
{
//Is this the "line of nodes" calculation choosing planes YZ (B coordinate system) and xy (A coordinate system)? (http://en.wikipedia.org/wiki/Euler_angles)
//The two planes are non-homologous, so this is a Tait<EFBFBD>Bryan angle formalism and not a proper Euler
//The two planes are non-homologous, so this is a Tait Bryan angle formalism and not a proper Euler
//Extrinsic rotations are equal to the reversed order intrinsic rotations so the above xyz extrinsic rotations (axes are fixed) are the same as the zy'x" intrinsic rotations (axes are refreshed after each rotation)
//that is why xy and YZ planes are chosen (this will describe a zy'x" intrinsic rotation) (see the figure on the left at http://en.wikipedia.org/wiki/Euler_angles under Tait<EFBFBD>Bryan angles)
//that is why xy and YZ planes are chosen (this will describe a zy'x" intrinsic rotation) (see the figure on the left at http://en.wikipedia.org/wiki/Euler_angles under Tait Bryan angles)
// x' = Nperp = N.cross(axis2)
// y' = N = axis2.cross(axis0)
// z' = z
@@ -866,7 +866,7 @@ int btGeneric6DofSpring2Constraint::get_limit_motor_info2(
// vel + f / m * (rotational ? -1 : 1)
// so in theory this should be set here for m_constraintError
// (with m_constraintError we set a desired velocity for the affected body(es))
// however in practice any value is fine as long as it is greater then the "proper" velocity,
// however in practice any value is fine as long as it is greater than the "proper" velocity,
// because the m_lowerLimit and the m_upperLimit will determinate the strength of the final pulling force
// so it is much simpler (and more robust) just to simply use inf (with the proper sign)
// (Even with our best intent the "new" velocity is only an estimation. If we underestimate

View File

@@ -294,7 +294,7 @@ protected:
bool m_hasStaticBody;
int m_flags;
btGeneric6DofSpring2Constraint& operator=(btGeneric6DofSpring2Constraint&)
btGeneric6DofSpring2Constraint& operator=(const btGeneric6DofSpring2Constraint&)
{
btAssert(0);
return *this;

View File

@@ -352,9 +352,9 @@ void btMultiBody::finalizeMultiDof()
updateLinksDofOffsets();
}
int btMultiBody::getParent(int i) const
int btMultiBody::getParent(int link_num) const
{
return m_links[i].m_parent;
return m_links[link_num].m_parent;
}
btScalar btMultiBody::getLinkMass(int i) const

View File

@@ -65,7 +65,7 @@ public:
virtual ~btMultiBody();
//note: fixed link collision with parent is always disabled
void setupFixed(int linkIndex,
void setupFixed(int i, //linkIndex
btScalar mass,
const btVector3 &inertia,
int parent,
@@ -83,7 +83,7 @@ public:
const btVector3 &thisPivotToThisComOffset,
bool disableParentCollision);
void setupRevolute(int linkIndex, // 0 to num_links-1
void setupRevolute(int i, // 0 to num_links-1
btScalar mass,
const btVector3 &inertia,
int parentIndex,
@@ -93,7 +93,7 @@ public:
const btVector3 &thisPivotToThisComOffset, // vector from joint axis to my COM, in MY frame
bool disableParentCollision = false);
void setupSpherical(int linkIndex, // 0 to num_links-1
void setupSpherical(int i, // linkIndex, 0 to num_links-1
btScalar mass,
const btVector3 &inertia,
int parent,
@@ -277,15 +277,15 @@ public:
//
// transform vectors in local frame of link i to world frame (or vice versa)
//
btVector3 localPosToWorld(int i, const btVector3 &vec) const;
btVector3 localDirToWorld(int i, const btVector3 &vec) const;
btVector3 worldPosToLocal(int i, const btVector3 &vec) const;
btVector3 worldDirToLocal(int i, const btVector3 &vec) const;
btVector3 localPosToWorld(int i, const btVector3 &local_pos) const;
btVector3 localDirToWorld(int i, const btVector3 &local_dir) const;
btVector3 worldPosToLocal(int i, const btVector3 &world_pos) const;
btVector3 worldDirToLocal(int i, const btVector3 &world_dir) const;
//
// transform a frame in local coordinate to a frame in world coordinate
//
btMatrix3x3 localFrameToWorld(int i, const btMatrix3x3 &mat) const;
btMatrix3x3 localFrameToWorld(int i, const btMatrix3x3 &local_frame) const;
//
// calculate kinetic energy and angular momentum
@@ -576,11 +576,11 @@ public:
{
return m_internalNeedsJointFeedback;
}
void forwardKinematics(btAlignedObjectArray<btQuaternion> & scratch_q, btAlignedObjectArray<btVector3> & scratch_m);
void forwardKinematics(btAlignedObjectArray<btQuaternion>& world_to_local, btAlignedObjectArray<btVector3> & local_origin);
void compTreeLinkVelocities(btVector3 * omega, btVector3 * vel) const;
void updateCollisionObjectWorldTransforms(btAlignedObjectArray<btQuaternion> & scratch_q, btAlignedObjectArray<btVector3> & scratch_m);
void updateCollisionObjectWorldTransforms(btAlignedObjectArray<btQuaternion> & world_to_local, btAlignedObjectArray<btVector3> & local_origin);
virtual int calculateSerializeBufferSize() const;

View File

@@ -45,14 +45,14 @@ subject to the following restrictions:
int btGetNumHardwareThreads()
{
return btMin<int>(BT_MAX_THREAD_COUNT, std::thread::hardware_concurrency());
return btMax(1u, btMin(BT_MAX_THREAD_COUNT, std::thread::hardware_concurrency()));
}
#else
int btGetNumHardwareThreads()
{
return btMin<int>(BT_MAX_THREAD_COUNT, sysconf(_SC_NPROCESSORS_ONLN));
return btMax(1, btMin<int>(BT_MAX_THREAD_COUNT, sysconf(_SC_NPROCESSORS_ONLN)));
}
#endif