2015-06-21 20:24:36 +00:00
# ifndef SHARED_MEMORY_COMMANDS_H
# define SHARED_MEMORY_COMMANDS_H
//this is a very experimental draft of commands. We will iterate on this API (commands, arguments etc)
2015-09-17 06:09:10 +00:00
# include "SharedMemoryPublic.h"
2015-07-15 22:23:40 +00:00
# ifdef __GNUC__
2018-09-23 21:17:31 +00:00
# include <stdint.h>
typedef int32_t smInt32_t ;
typedef int64_t smInt64_t ;
typedef uint32_t smUint32_t ;
typedef uint64_t smUint64_t ;
2015-07-15 22:23:40 +00:00
# elif defined(_MSC_VER)
2018-09-23 21:17:31 +00:00
typedef __int32 smInt32_t ;
typedef __int64 smInt64_t ;
typedef unsigned __int32 smUint32_t ;
typedef unsigned __int64 smUint64_t ;
2015-07-15 22:23:40 +00:00
# else
2018-09-23 21:17:31 +00:00
typedef int smInt32_t ;
typedef long long int smInt64_t ;
typedef unsigned int smUint32_t ;
typedef unsigned long long int smUint64_t ;
2015-07-15 22:23:40 +00:00
# endif
2018-06-16 15:14:00 +00:00
# ifdef __APPLE__
2019-08-11 20:59:24 +00:00
# define SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE (1024 * 1024)
2018-06-16 15:14:00 +00:00
# else
2018-09-23 21:17:31 +00:00
# define SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE (8 * 1024 * 1024)
2018-06-16 15:14:00 +00:00
# endif
2015-06-21 20:24:36 +00:00
# define SHARED_MEMORY_SERVER_TEST_C
2019-07-11 00:21:18 +00:00
# define MAX_DEGREE_OF_FREEDOM 128
2015-08-02 21:00:43 +00:00
# define MAX_NUM_SENSORS 256
2015-06-21 20:24:36 +00:00
# define MAX_URDF_FILENAME_LENGTH 1024
2016-06-04 02:03:56 +00:00
# define MAX_SDF_FILENAME_LENGTH 1024
2015-08-20 05:51:16 +00:00
# define MAX_FILENAME_LENGTH MAX_URDF_FILENAME_LENGTH
2016-04-24 00:29:46 +00:00
# define MAX_NUM_LINKS MAX_DEGREE_OF_FREEDOM
2015-06-21 20:24:36 +00:00
2018-10-26 17:18:51 +00:00
2018-09-23 21:17:31 +00:00
struct TmpFloat3
2015-11-23 04:50:32 +00:00
{
2018-09-23 21:17:31 +00:00
float m_x ;
float m_y ;
float m_z ;
2015-11-23 04:50:32 +00:00
} ;
# ifdef _WIN32
__inline
# else
inline
# endif
2018-09-23 21:17:31 +00:00
TmpFloat3
CreateTmpFloat3 ( float x , float y , float z )
{
TmpFloat3 tmp ;
tmp . m_x = x ;
tmp . m_y = y ;
tmp . m_z = z ;
return tmp ;
2015-11-23 04:50:32 +00:00
}
2016-06-04 02:03:56 +00:00
enum EnumSdfArgsUpdateFlags
{
2018-09-23 21:17:31 +00:00
SDF_ARGS_FILE_NAME = 1 ,
2016-06-04 02:03:56 +00:00
} ;
struct SdfArgs
{
char m_sdfFileName [ MAX_URDF_FILENAME_LENGTH ] ;
2018-09-23 21:17:31 +00:00
int m_useMultiBody ;
2017-08-14 21:59:41 +00:00
double m_globalScaling ;
2016-06-04 02:03:56 +00:00
} ;
2016-11-12 02:07:42 +00:00
struct FileArgs
{
char m_fileName [ MAX_URDF_FILENAME_LENGTH ] ;
2017-12-28 18:05:51 +00:00
int m_stateId ;
} ;
enum EnumLoadStateArgsUpdateFlags
{
2018-09-23 21:17:31 +00:00
CMD_LOAD_STATE_HAS_STATEID = 1 ,
CMD_LOAD_STATE_HAS_FILENAME = 2 ,
2016-11-12 02:07:42 +00:00
} ;
2015-07-31 06:22:44 +00:00
enum EnumUrdfArgsUpdateFlags
{
2018-09-23 21:17:31 +00:00
URDF_ARGS_FILE_NAME = 1 ,
URDF_ARGS_INITIAL_POSITION = 2 ,
URDF_ARGS_INITIAL_ORIENTATION = 4 ,
URDF_ARGS_USE_MULTIBODY = 8 ,
URDF_ARGS_USE_FIXED_BASE = 16 ,
2017-08-14 21:59:41 +00:00
URDF_ARGS_HAS_CUSTOM_URDF_FLAGS = 32 ,
2018-09-23 21:17:31 +00:00
URDF_ARGS_USE_GLOBAL_SCALING = 64 ,
2015-07-31 06:22:44 +00:00
} ;
2015-06-21 20:24:36 +00:00
struct UrdfArgs
{
2015-07-23 18:51:25 +00:00
char m_urdfFileName [ MAX_URDF_FILENAME_LENGTH ] ;
double m_initialPosition [ 3 ] ;
double m_initialOrientation [ 4 ] ;
int m_useMultiBody ;
int m_useFixedBase ;
2017-03-27 15:30:20 +00:00
int m_urdfFlags ;
2017-08-14 21:59:41 +00:00
double m_globalScaling ;
2015-06-21 20:24:36 +00:00
} ;
2016-12-31 22:43:15 +00:00
struct MjcfArgs
{
char m_mjcfFileName [ MAX_URDF_FILENAME_LENGTH ] ;
int m_useMultiBody ;
2017-05-10 22:01:25 +00:00
int m_flags ;
2016-12-31 22:43:15 +00:00
} ;
2015-07-09 21:04:58 +00:00
2017-08-28 02:34:00 +00:00
struct b3SearchPathfArgs
{
char m_path [ MAX_FILENAME_LENGTH ] ;
} ;
2017-09-23 02:17:57 +00:00
enum CustomCommandEnum
{
2018-09-23 21:17:31 +00:00
CMD_CUSTOM_COMMAND_LOAD_PLUGIN = 1 ,
CMD_CUSTOM_COMMAND_UNLOAD_PLUGIN = 2 ,
CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND = 4 ,
CMD_CUSTOM_COMMAND_LOAD_PLUGIN_POSTFIX = 8 ,
2017-09-23 02:17:57 +00:00
} ;
struct b3CustomCommand
{
int m_pluginUniqueId ;
2017-09-24 01:05:23 +00:00
b3PluginArguments m_arguments ;
2017-09-23 02:17:57 +00:00
char m_pluginPath [ MAX_FILENAME_LENGTH ] ;
2017-10-03 22:00:52 +00:00
char m_postFix [ MAX_FILENAME_LENGTH ] ;
2020-10-07 03:19:39 +00:00
int m_startingReturnBytes ;
2017-09-23 02:17:57 +00:00
} ;
struct b3CustomCommandResultArgs
{
int m_pluginUniqueId ;
int m_executeCommandResult ;
2020-10-07 03:19:39 +00:00
int m_returnDataType ;
int m_returnDataSizeInBytes ;
2020-10-07 15:24:33 +00:00
int m_returnDataStart ;
2017-09-23 02:17:57 +00:00
} ;
2017-08-28 02:34:00 +00:00
2015-07-09 21:04:58 +00:00
struct BulletDataStreamArgs
{
2015-08-20 05:51:16 +00:00
char m_bulletFileName [ MAX_FILENAME_LENGTH ] ;
2015-07-21 06:35:29 +00:00
int m_bodyUniqueId ;
2017-03-29 22:37:33 +00:00
char m_bodyName [ MAX_FILENAME_LENGTH ] ;
2015-07-09 21:04:58 +00:00
} ;
2017-05-09 17:44:33 +00:00
enum EnumChangeDynamicsInfoFlags
2017-05-02 05:18:54 +00:00
{
2018-09-23 21:17:31 +00:00
CHANGE_DYNAMICS_INFO_SET_MASS = 1 ,
CHANGE_DYNAMICS_INFO_SET_COM = 2 ,
CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION = 4 ,
CHANGE_DYNAMICS_INFO_SET_SPINNING_FRICTION = 8 ,
CHANGE_DYNAMICS_INFO_SET_ROLLING_FRICTION = 16 ,
CHANGE_DYNAMICS_INFO_SET_RESTITUTION = 32 ,
CHANGE_DYNAMICS_INFO_SET_LINEAR_DAMPING = 64 ,
CHANGE_DYNAMICS_INFO_SET_ANGULAR_DAMPING = 128 ,
CHANGE_DYNAMICS_INFO_SET_CONTACT_STIFFNESS_AND_DAMPING = 256 ,
2017-06-07 16:37:28 +00:00
CHANGE_DYNAMICS_INFO_SET_FRICTION_ANCHOR = 512 ,
2017-12-21 00:56:31 +00:00
CHANGE_DYNAMICS_INFO_SET_LOCAL_INERTIA_DIAGONAL = 1024 ,
2018-02-17 03:44:33 +00:00
CHANGE_DYNAMICS_INFO_SET_CCD_SWEPT_SPHERE_RADIUS = 2048 ,
2018-05-23 03:26:00 +00:00
CHANGE_DYNAMICS_INFO_SET_CONTACT_PROCESSING_THRESHOLD = 4096 ,
2018-06-16 04:26:26 +00:00
CHANGE_DYNAMICS_INFO_SET_ACTIVATION_STATE = 8192 ,
2019-02-05 05:06:43 +00:00
CHANGE_DYNAMICS_INFO_SET_JOINT_DAMPING = 16384 ,
2019-03-08 05:13:00 +00:00
CHANGE_DYNAMICS_INFO_SET_ANISOTROPIC_FRICTION = 32768 ,
2019-03-09 17:23:16 +00:00
CHANGE_DYNAMICS_INFO_SET_MAX_JOINT_VELOCITY = 1 < < 16 ,
unsupported: expose collisionMargin to changeDynamics/getDynamicsInfo.
add cube_convex.urdf for testing this collisionMargin. Test script:
import pybullet as p
import time
p.connect(p.GUI)
plane = p.loadURDF("plane_implicit.urdf")
cube = p.loadURDF("cube_convex.urdf",[0,0,1])
p.setGravity(0,0,-10)
while (1):
p.stepSimulation()
pts = p.getContactPoints()
p.changeDynamics(plane,-1,collisionMargin=0.3)
p.changeDynamics(cube,-1,collisionMargin=0.3)
print("===================")
print("cube pos=", p.getBasePositionAndOrientation(cube)[0])
print("margin=", p.getDynamicsInfo(plane,-1)[11])
#time.sleep(1./10.)
2020-02-15 01:36:40 +00:00
CHANGE_DYNAMICS_INFO_SET_COLLISION_MARGIN = 1 < < 17 ,
2020-07-08 02:42:23 +00:00
CHANGE_DYNAMICS_INFO_SET_JOINT_LIMITS = 1 < < 18 ,
CHANGE_DYNAMICS_INFO_SET_JOINT_LIMIT_MAX_FORCE = 1 < < 19 ,
2020-11-12 06:41:33 +00:00
CHANGE_DYNAMICS_INFO_SET_DYNAMIC_TYPE = 1 < < 20 ,
2017-05-02 05:18:54 +00:00
} ;
2017-05-09 17:44:33 +00:00
struct ChangeDynamicsInfoArgs
2017-05-02 05:18:54 +00:00
{
int m_bodyUniqueId ;
int m_linkIndex ;
double m_mass ;
double m_COM [ 3 ] ;
2017-05-04 04:47:53 +00:00
double m_lateralFriction ;
2017-05-27 01:14:38 +00:00
double m_spinningFriction ;
double m_rollingFriction ;
double m_restitution ;
2017-06-05 05:04:16 +00:00
double m_linearDamping ;
double m_angularDamping ;
2017-06-07 15:37:42 +00:00
double m_contactStiffness ;
double m_contactDamping ;
2017-12-21 00:56:31 +00:00
double m_localInertiaDiagonal [ 3 ] ;
2017-06-07 16:37:28 +00:00
int m_frictionAnchor ;
2018-02-17 03:44:33 +00:00
double m_ccdSweptSphereRadius ;
2018-05-23 03:26:00 +00:00
double m_contactProcessingThreshold ;
2018-06-16 04:26:26 +00:00
int m_activationState ;
2019-02-05 05:06:43 +00:00
double m_jointDamping ;
2019-03-08 05:13:00 +00:00
double m_anisotropicFriction [ 3 ] ;
2019-03-09 17:23:16 +00:00
double m_maxJointVelocity ;
unsupported: expose collisionMargin to changeDynamics/getDynamicsInfo.
add cube_convex.urdf for testing this collisionMargin. Test script:
import pybullet as p
import time
p.connect(p.GUI)
plane = p.loadURDF("plane_implicit.urdf")
cube = p.loadURDF("cube_convex.urdf",[0,0,1])
p.setGravity(0,0,-10)
while (1):
p.stepSimulation()
pts = p.getContactPoints()
p.changeDynamics(plane,-1,collisionMargin=0.3)
p.changeDynamics(cube,-1,collisionMargin=0.3)
print("===================")
print("cube pos=", p.getBasePositionAndOrientation(cube)[0])
print("margin=", p.getDynamicsInfo(plane,-1)[11])
#time.sleep(1./10.)
2020-02-15 01:36:40 +00:00
double m_collisionMargin ;
2020-07-08 02:42:23 +00:00
double m_jointLowerLimit ;
double m_jointUpperLimit ;
double m_jointLimitForce ;
2020-11-12 06:41:33 +00:00
int m_dynamicType ;
2017-05-02 05:18:54 +00:00
} ;
2017-05-09 17:31:28 +00:00
struct GetDynamicsInfoArgs
2017-05-08 05:21:38 +00:00
{
int m_bodyUniqueId ;
int m_linkIndex ;
} ;
2015-06-22 22:30:57 +00:00
struct SetJointFeedbackArgs
{
int m_bodyUniqueId ;
int m_linkId ;
2015-07-23 18:51:25 +00:00
int m_isEnabled ;
2015-06-22 22:30:57 +00:00
} ;
2015-10-14 05:23:28 +00:00
enum EnumInitPoseFlags
{
2018-09-23 21:17:31 +00:00
INIT_POSE_HAS_INITIAL_POSITION = 1 ,
INIT_POSE_HAS_INITIAL_ORIENTATION = 2 ,
INIT_POSE_HAS_JOINT_STATE = 4 ,
2016-11-28 23:11:34 +00:00
INIT_POSE_HAS_BASE_LINEAR_VELOCITY = 8 ,
INIT_POSE_HAS_BASE_ANGULAR_VELOCITY = 16 ,
2018-09-23 21:17:31 +00:00
INIT_POSE_HAS_JOINT_VELOCITY = 32 ,
2020-05-17 20:46:11 +00:00
INIT_POSE_HAS_SCALING = 64 ,
2015-10-14 05:23:28 +00:00
} ;
2015-09-17 06:09:10 +00:00
2015-07-22 04:46:28 +00:00
///InitPoseArgs is mainly to initialize (teleport) the robot in a particular position
///No motors or controls are needed to initialize the pose. It is similar to
///moving a robot to a starting place, while it is switched off. It is only called
///at the start of a robot control session. All velocities and control forces are cleared to zero.
struct InitPoseArgs
{
int m_bodyUniqueId ;
2016-06-24 14:31:17 +00:00
int m_hasInitialStateQ [ MAX_DEGREE_OF_FREEDOM ] ;
2015-07-22 04:46:28 +00:00
double m_initialStateQ [ MAX_DEGREE_OF_FREEDOM ] ;
2016-11-28 23:11:34 +00:00
int m_hasInitialStateQdot [ MAX_DEGREE_OF_FREEDOM ] ;
double m_initialStateQdot [ MAX_DEGREE_OF_FREEDOM ] ;
2020-05-17 20:46:11 +00:00
double m_scaling [ 3 ] ;
2015-07-22 04:46:28 +00:00
} ;
2015-08-20 05:51:16 +00:00
struct RequestDebugLinesArgs
{
int m_debugMode ;
2018-09-23 21:17:31 +00:00
int m_startingLineIndex ;
2015-08-20 05:51:16 +00:00
} ;
2016-05-31 17:23:04 +00:00
struct RequestPixelDataArgs
{
2016-06-01 18:04:10 +00:00
float m_viewMatrix [ 16 ] ;
float m_projectionMatrix [ 16 ] ;
int m_startPixelIndex ;
2016-06-07 23:11:58 +00:00
int m_pixelWidth ;
int m_pixelHeight ;
2016-11-17 23:15:52 +00:00
float m_lightDirection [ 3 ] ;
2018-09-23 21:17:31 +00:00
float m_lightColor [ 3 ] ;
float m_lightDistance ;
float m_lightAmbientCoeff ;
float m_lightDiffuseCoeff ;
float m_lightSpecularCoeff ;
int m_hasShadow ;
2017-12-28 20:37:07 +00:00
int m_flags ;
2018-03-19 01:45:54 +00:00
float m_projectiveTextureViewMatrix [ 16 ] ;
float m_projectiveTextureProjectionMatrix [ 16 ] ;
2016-05-31 17:23:04 +00:00
} ;
2016-06-01 18:04:10 +00:00
enum EnumRequestPixelDataUpdateFlags
{
2018-09-23 21:17:31 +00:00
REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES = 1 ,
REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT = 2 ,
REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION = 4 ,
REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR = 8 ,
REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE = 16 ,
REQUEST_PIXEL_ARGS_SET_SHADOW = 32 ,
REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF = 64 ,
REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF = 128 ,
REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF = 256 ,
2017-12-28 20:37:07 +00:00
REQUEST_PIXEL_ARGS_HAS_FLAGS = 512 ,
2018-09-23 21:17:31 +00:00
REQUEST_PIXEL_ARGS_HAS_PROJECTIVE_TEXTURE_MATRICES = 1024 ,
2017-12-28 20:37:07 +00:00
2016-07-13 01:16:13 +00:00
//don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h
2018-09-23 21:17:31 +00:00
2016-06-01 18:04:10 +00:00
} ;
2016-11-10 05:01:04 +00:00
enum EnumRequestContactDataUpdateFlags
{
2018-09-23 21:17:31 +00:00
CMD_REQUEST_CONTACT_POINT_HAS_QUERY_MODE = 1 ,
CMD_REQUEST_CONTACT_POINT_HAS_CLOSEST_DISTANCE_THRESHOLD = 2 ,
2016-11-20 01:13:56 +00:00
CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER = 4 ,
CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER = 8 ,
2018-09-22 20:17:09 +00:00
CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_A = 16 ,
CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_B = 32 ,
CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_POSITION_A = 64 ,
CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_POSITION_B = 128 ,
2018-09-23 21:17:31 +00:00
CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_ORIENTATION_A = 256 ,
CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_ORIENTATION_B = 512 ,
2018-09-22 20:17:09 +00:00
2016-11-10 05:01:04 +00:00
} ;
2016-12-27 03:40:09 +00:00
struct RequestRaycastIntersections
{
2018-06-15 14:47:04 +00:00
// The number of threads that Bullet may use to perform the ray casts.
// 0: Let Bullet decide
// 1: Use a single thread (i.e. no multi-threading)
// 2 or more: Number of threads to use.
int m_numThreads ;
2018-06-16 19:28:21 +00:00
int m_numCommandRays ;
//m_numCommandRays command rays are stored in m_fromToRays
b3RayData m_fromToRays [ MAX_RAY_INTERSECTION_BATCH_SIZE ] ;
2018-09-23 21:17:31 +00:00
2018-06-16 19:28:21 +00:00
int m_numStreamingRays ;
2018-10-11 06:31:50 +00:00
//optional m_parentObjectUniqueId (-1 for unused)
int m_parentObjectUniqueId ;
int m_parentLinkIndex ;
2020-05-08 06:23:24 +00:00
int m_reportHitNumber ;
2020-05-08 18:57:25 +00:00
int m_collisionFilterMask ;
2020-05-09 09:42:47 +00:00
double m_fractionEpsilon ;
2018-06-16 19:28:21 +00:00
//streaming ray data stored in shared memory streaming part. (size m_numStreamingRays )
2016-12-27 03:40:09 +00:00
} ;
struct SendRaycastHits
{
int m_numRaycastHits ;
2018-06-16 19:28:21 +00:00
// Actual ray result data stored in shared memory streaming part.
2016-12-27 03:40:09 +00:00
} ;
2016-09-01 20:30:07 +00:00
struct RequestContactDataArgs
{
2018-09-23 21:17:31 +00:00
int m_startingContactPointIndex ;
int m_objectAIndexFilter ;
2016-09-01 20:30:07 +00:00
int m_objectBIndexFilter ;
2016-11-20 01:13:56 +00:00
int m_linkIndexAIndexFilter ;
int m_linkIndexBIndexFilter ;
2016-11-10 05:01:04 +00:00
double m_closestDistanceThreshold ;
2018-09-22 20:17:09 +00:00
int m_collisionShapeA ;
int m_collisionShapeB ;
double m_collisionShapePositionA [ 3 ] ;
double m_collisionShapePositionB [ 3 ] ;
double m_collisionShapeOrientationA [ 4 ] ;
double m_collisionShapeOrientationB [ 4 ] ;
2018-09-23 21:17:31 +00:00
2016-11-10 19:22:22 +00:00
int m_mode ;
} ;
struct RequestOverlappingObjectsArgs
{
int m_startingOverlappingObjectIndex ;
2016-11-10 05:01:04 +00:00
double m_aabbQueryMin [ 3 ] ;
double m_aabbQueryMax [ 3 ] ;
2016-09-01 20:30:07 +00:00
} ;
2016-06-01 18:04:10 +00:00
2016-10-19 05:05:28 +00:00
struct RequestVisualShapeDataArgs
{
int m_bodyUniqueId ;
int m_startingVisualShapeIndex ;
} ;
2018-01-04 03:17:28 +00:00
struct RequestCollisionShapeDataArgs
{
int m_bodyUniqueId ;
int m_linkIndex ;
} ;
2017-05-13 16:18:36 +00:00
enum EnumUpdateVisualShapeData
{
2018-09-23 21:17:31 +00:00
CMD_UPDATE_VISUAL_SHAPE_TEXTURE = 1 ,
CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR = 2 ,
CMD_UPDATE_VISUAL_SHAPE_SPECULAR_COLOR = 4 ,
* add textured models of ball.vtk (obj/mtl) and torus (obj/mtl) and cloth.
1) allow to render deformables in 'getCameraImage', for TinyRenderer (tested OK) and EGL (untested)
2) allow to have textures for deformables. See deformable_ball.py, deformable_anchor.py and deformable_torus.py for examples
3) deformables: allow to request simulation mesh data (even if there is a render mesh) See deformable_anchor.py for an example usage
data = p.getMeshData(clothId, -1, flags=p.MESH_DATA_SIMULATION_MESH)
4) fix deletion of deformables, thanks to Fychuyan, https://github.com/bulletphysics/bullet3/pull/3048
5) allow to enable and disable double-sided rendering, p.changeVisualShape(objectUid, linkIndex, flags=p.VISUAL_SHAPE_DOUBLE_SIDED)
6) fix GripperGraspExample, model not found
7) Fix deformable anchor not attaching to multibody with object unique id of 0
8) Fix issue with assignment of unique ids in TinyRenderer/EGL renderer (always use broadphase uid)
9) Avoid crash/issue of simulation with pinned vertices (mass 0) in btDeformableBackwardEulerObjective::applyExplicitForce
10) Store uv/normal in btSoftBody::RenderNode to allow textured meshes
11) (uncomment in btSoftBodyHelpers.cpp): dump vertices and indices in obj wavefront format, when loading a VTK file, for quicker creation of a (textured) surface mesh
12) allow interpolateRenderMesh also for old position-based soft bodies (not only the shiny new FEM deformables)
13) fix a few premake targets
14) update build_visual_studio_vr_pybullet_double_cmake.bat so it suits c:\python37 and installs locally
for local install of Bullet, see also this example https://github.com/erwincoumans/hello_bullet_cmake
2020-09-12 08:03:04 +00:00
CMD_UPDATE_VISUAL_SHAPE_FLAGS = 8 ,
2017-05-13 16:18:36 +00:00
} ;
* add textured models of ball.vtk (obj/mtl) and torus (obj/mtl) and cloth.
1) allow to render deformables in 'getCameraImage', for TinyRenderer (tested OK) and EGL (untested)
2) allow to have textures for deformables. See deformable_ball.py, deformable_anchor.py and deformable_torus.py for examples
3) deformables: allow to request simulation mesh data (even if there is a render mesh) See deformable_anchor.py for an example usage
data = p.getMeshData(clothId, -1, flags=p.MESH_DATA_SIMULATION_MESH)
4) fix deletion of deformables, thanks to Fychuyan, https://github.com/bulletphysics/bullet3/pull/3048
5) allow to enable and disable double-sided rendering, p.changeVisualShape(objectUid, linkIndex, flags=p.VISUAL_SHAPE_DOUBLE_SIDED)
6) fix GripperGraspExample, model not found
7) Fix deformable anchor not attaching to multibody with object unique id of 0
8) Fix issue with assignment of unique ids in TinyRenderer/EGL renderer (always use broadphase uid)
9) Avoid crash/issue of simulation with pinned vertices (mass 0) in btDeformableBackwardEulerObjective::applyExplicitForce
10) Store uv/normal in btSoftBody::RenderNode to allow textured meshes
11) (uncomment in btSoftBodyHelpers.cpp): dump vertices and indices in obj wavefront format, when loading a VTK file, for quicker creation of a (textured) surface mesh
12) allow interpolateRenderMesh also for old position-based soft bodies (not only the shiny new FEM deformables)
13) fix a few premake targets
14) update build_visual_studio_vr_pybullet_double_cmake.bat so it suits c:\python37 and installs locally
for local install of Bullet, see also this example https://github.com/erwincoumans/hello_bullet_cmake
2020-09-12 08:03:04 +00:00
2016-10-21 06:40:30 +00:00
struct UpdateVisualShapeDataArgs
{
2018-09-23 21:17:31 +00:00
int m_bodyUniqueId ;
int m_jointIndex ;
int m_shapeIndex ;
int m_textureUniqueId ;
2017-05-13 16:18:36 +00:00
double m_rgbaColor [ 4 ] ;
2017-06-01 19:32:44 +00:00
double m_specularColor [ 3 ] ;
* add textured models of ball.vtk (obj/mtl) and torus (obj/mtl) and cloth.
1) allow to render deformables in 'getCameraImage', for TinyRenderer (tested OK) and EGL (untested)
2) allow to have textures for deformables. See deformable_ball.py, deformable_anchor.py and deformable_torus.py for examples
3) deformables: allow to request simulation mesh data (even if there is a render mesh) See deformable_anchor.py for an example usage
data = p.getMeshData(clothId, -1, flags=p.MESH_DATA_SIMULATION_MESH)
4) fix deletion of deformables, thanks to Fychuyan, https://github.com/bulletphysics/bullet3/pull/3048
5) allow to enable and disable double-sided rendering, p.changeVisualShape(objectUid, linkIndex, flags=p.VISUAL_SHAPE_DOUBLE_SIDED)
6) fix GripperGraspExample, model not found
7) Fix deformable anchor not attaching to multibody with object unique id of 0
8) Fix issue with assignment of unique ids in TinyRenderer/EGL renderer (always use broadphase uid)
9) Avoid crash/issue of simulation with pinned vertices (mass 0) in btDeformableBackwardEulerObjective::applyExplicitForce
10) Store uv/normal in btSoftBody::RenderNode to allow textured meshes
11) (uncomment in btSoftBodyHelpers.cpp): dump vertices and indices in obj wavefront format, when loading a VTK file, for quicker creation of a (textured) surface mesh
12) allow interpolateRenderMesh also for old position-based soft bodies (not only the shiny new FEM deformables)
13) fix a few premake targets
14) update build_visual_studio_vr_pybullet_double_cmake.bat so it suits c:\python37 and installs locally
for local install of Bullet, see also this example https://github.com/erwincoumans/hello_bullet_cmake
2020-09-12 08:03:04 +00:00
int m_flags ;
2016-10-21 06:40:30 +00:00
} ;
struct LoadTextureArgs
{
2018-09-23 21:17:31 +00:00
char m_textureFileName [ MAX_FILENAME_LENGTH ] ;
2016-10-21 06:40:30 +00:00
} ;
2017-06-30 20:35:07 +00:00
struct b3LoadTextureResultArgs
{
int m_textureUniqueId ;
} ;
2016-10-19 05:05:28 +00:00
struct SendVisualShapeDataArgs
{
int m_bodyUniqueId ;
2018-09-23 21:17:31 +00:00
int m_startingVisualShapeIndex ;
int m_numVisualShapesCopied ;
int m_numRemainingVisualShapes ;
2016-10-19 05:05:28 +00:00
} ;
2018-01-04 03:17:28 +00:00
struct SendCollisionShapeDataArgs
{
int m_bodyUniqueId ;
int m_linkIndex ;
int m_numCollisionShapes ;
} ;
2016-06-01 18:04:10 +00:00
2015-08-20 05:51:16 +00:00
struct SendDebugLinesArgs
{
2018-09-23 21:17:31 +00:00
int m_startingLineIndex ;
2015-08-20 05:51:16 +00:00
int m_numDebugLines ;
2018-09-23 21:17:31 +00:00
int m_numRemainingDebugLines ;
2015-08-20 05:51:16 +00:00
} ;
2016-05-31 17:23:04 +00:00
struct SendPixelDataArgs
{
int m_imageWidth ;
int m_imageHeight ;
2018-09-23 21:17:31 +00:00
int m_startingPixelIndex ;
int m_numPixelsCopied ;
int m_numRemainingPixels ;
2016-05-31 17:23:04 +00:00
} ;
2015-09-25 05:42:22 +00:00
struct PickBodyArgs
{
2018-09-23 21:17:31 +00:00
double m_rayFromWorld [ 3 ] ;
double m_rayToWorld [ 3 ] ;
2015-09-25 05:42:22 +00:00
} ;
2015-07-22 04:46:28 +00:00
///Controlling a robot involves sending the desired state to its joint motor controllers.
///The control mode determines the state variables used for motor control.
2015-06-21 20:24:36 +00:00
struct SendDesiredStateArgs
{
int m_bodyUniqueId ;
2015-07-14 15:34:02 +00:00
int m_controlMode ;
2018-09-23 21:17:31 +00:00
2015-08-20 05:51:16 +00:00
//PD parameters in case m_controlMode == CONTROL_MODE_POSITION_VELOCITY_PD
2018-09-23 21:17:31 +00:00
double m_Kp [ MAX_DEGREE_OF_FREEDOM ] ; //indexed by degree of freedom, 6 for base, and then the dofs for each link
double m_Kd [ MAX_DEGREE_OF_FREEDOM ] ; //indexed by degree of freedom, 6 for base, and then the dofs for each link
2017-11-22 01:05:28 +00:00
double m_rhsClamp [ MAX_DEGREE_OF_FREEDOM ] ;
2015-08-20 05:51:16 +00:00
2018-09-23 21:17:31 +00:00
int m_hasDesiredStateFlags [ MAX_DEGREE_OF_FREEDOM ] ;
2015-07-15 22:23:40 +00:00
//desired state is only written by the client, read-only access by server is expected
2015-08-20 05:51:16 +00:00
2018-09-23 21:17:31 +00:00
//m_desiredStateQ is indexed by position variables,
2015-08-20 05:51:16 +00:00
//starting with 3 base position variables, 4 base orientation variables (quaternion), then link position variables
2018-09-23 21:17:31 +00:00
double m_desiredStateQ [ MAX_DEGREE_OF_FREEDOM ] ;
2015-08-20 05:51:16 +00:00
//m_desiredStateQdot is index by velocity degrees of freedom, 3 linear and 3 angular variables for the base and then link velocity variables
2018-09-23 21:17:31 +00:00
double m_desiredStateQdot [ MAX_DEGREE_OF_FREEDOM ] ;
2015-07-15 22:23:40 +00:00
//m_desiredStateForceTorque is either the actual applied force/torque (in CONTROL_MODE_TORQUE) or
2015-08-20 05:51:16 +00:00
//or the maximum applied force/torque for the PD/motor/constraint to reach the desired velocity in CONTROL_MODE_VELOCITY and CONTROL_MODE_POSITION_VELOCITY_PD mode
//indexed by degree of freedom, 6 dof base, and then dofs for each link
2018-09-23 21:17:31 +00:00
double m_desiredStateForceTorque [ MAX_DEGREE_OF_FREEDOM ] ;
2015-06-21 20:24:36 +00:00
} ;
2016-06-04 02:03:56 +00:00
enum EnumSimDesiredStateUpdateFlags
{
2018-09-23 21:17:31 +00:00
SIM_DESIRED_STATE_HAS_Q = 1 ,
SIM_DESIRED_STATE_HAS_QDOT = 2 ,
SIM_DESIRED_STATE_HAS_KD = 4 ,
SIM_DESIRED_STATE_HAS_KP = 8 ,
SIM_DESIRED_STATE_HAS_MAX_FORCE = 16 ,
2018-11-13 22:32:18 +00:00
SIM_DESIRED_STATE_HAS_RHS_CLAMP = 32 ,
2016-06-04 02:03:56 +00:00
} ;
2015-07-31 06:22:44 +00:00
enum EnumSimParamUpdateFlags
2015-07-22 04:46:28 +00:00
{
2018-09-23 21:17:31 +00:00
SIM_PARAM_UPDATE_DELTA_TIME = 1 ,
2019-04-15 01:20:20 +00:00
SIM_PARAM_UPDATE_GRAVITY = 1 < < 1 ,
SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS = 1 < < 2 ,
SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS = 1 < < 3 ,
SIM_PARAM_UPDATE_REAL_TIME_SIMULATION = 1 < < 4 ,
SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP = 1 < < 5 ,
SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS = 1 < < 6 ,
SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE = 1 < < 7 ,
SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD = 1 < < 8 ,
SIM_PARAM_UPDATE_COLLISION_FILTER_MODE = 1 < < 9 ,
SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD = 1 < < 10 ,
SIM_PARAM_ENABLE_CONE_FRICTION = 1 < < 11 ,
SIM_PARAM_ENABLE_FILE_CACHING = 1 < < 12 ,
SIM_PARAM_UPDATE_RESTITUTION_VELOCITY_THRESHOLD = 1 < < 13 ,
SIM_PARAM_UPDATE_DEFAULT_NON_CONTACT_ERP = 1 < < 14 ,
SIM_PARAM_UPDATE_DEFAULT_FRICTION_ERP = 1 < < 15 ,
SIM_PARAM_UPDATE_DETERMINISTIC_OVERLAPPING_PAIRS = 1 < < 16 ,
SIM_PARAM_UPDATE_CCD_ALLOWED_PENETRATION = 1 < < 17 ,
SIM_PARAM_UPDATE_JOINT_FEEDBACK_MODE = 1 < < 18 ,
SIM_PARAM_UPDATE_DEFAULT_GLOBAL_CFM = 1 < < 19 ,
SIM_PARAM_UPDATE_DEFAULT_FRICTION_CFM = 1 < < 20 ,
SIM_PARAM_UPDATE_SOLVER_RESIDULAL_THRESHOLD = 1 < < 21 ,
SIM_PARAM_UPDATE_CONTACT_SLOP = 1 < < 22 ,
SIM_PARAM_ENABLE_SAT = 1 < < 23 ,
SIM_PARAM_CONSTRAINT_SOLVER_TYPE = 1 < < 24 ,
SIM_PARAM_CONSTRAINT_MIN_SOLVER_ISLAND_SIZE = 1 < < 25 ,
SIM_PARAM_REPORT_CONSTRAINT_SOLVER_ANALYTICS = 1 < < 26 ,
2019-08-06 21:04:51 +00:00
SIM_PARAM_UPDATE_WARM_STARTING_FACTOR = 1 < < 27 ,
2019-10-17 23:59:15 +00:00
SIM_PARAM_UPDATE_ARTICULATED_WARM_STARTING_FACTOR = 1 < < 28 ,
2019-11-18 18:22:56 +00:00
SIM_PARAM_UPDATE_SPARSE_SDF = 1 < < 29 ,
2020-03-03 00:03:27 +00:00
SIM_PARAM_UPDATE_NUM_NONCONTACT_INNER_ITERATIONS = 1 < < 30 ,
2015-07-22 04:46:28 +00:00
} ;
2018-01-08 03:24:37 +00:00
enum EnumLoadSoftBodyUpdateFlags
2016-11-01 23:45:10 +00:00
{
2018-09-23 21:17:31 +00:00
LOAD_SOFT_BODY_FILE_NAME = 1 ,
2019-08-26 22:43:21 +00:00
LOAD_SOFT_BODY_UPDATE_SCALE = 1 < < 1 ,
LOAD_SOFT_BODY_UPDATE_MASS = 1 < < 2 ,
LOAD_SOFT_BODY_UPDATE_COLLISION_MARGIN = 1 < < 3 ,
LOAD_SOFT_BODY_INITIAL_POSITION = 1 < < 4 ,
2020-04-28 00:42:45 +00:00
LOAD_SOFT_BODY_INITIAL_ORIENTATION = 1 < < 5 ,
LOAD_SOFT_BODY_ADD_COROTATED_FORCE = 1 < < 6 ,
LOAD_SOFT_BODY_ADD_MASS_SPRING_FORCE = 1 < < 7 ,
LOAD_SOFT_BODY_ADD_GRAVITY_FORCE = 1 < < 8 ,
LOAD_SOFT_BODY_SET_COLLISION_HARDNESS = 1 < < 9 ,
LOAD_SOFT_BODY_SET_FRICTION_COEFFICIENT = 1 < < 10 ,
LOAD_SOFT_BODY_ADD_BENDING_SPRINGS = 1 < < 11 ,
LOAD_SOFT_BODY_ADD_NEOHOOKEAN_FORCE = 1 < < 12 ,
LOAD_SOFT_BODY_USE_SELF_COLLISION = 1 < < 13 ,
LOAD_SOFT_BODY_USE_FACE_CONTACT = 1 < < 14 ,
LOAD_SOFT_BODY_SIM_MESH = 1 < < 15 ,
LOAD_SOFT_BODY_SET_REPULSION_STIFFNESS = 1 < < 16 ,
2020-05-12 00:08:33 +00:00
LOAD_SOFT_BODY_SET_DAMPING_SPRING_MODE = 1 < < 17 ,
2020-05-26 23:49:52 +00:00
LOAD_SOFT_BODY_SET_GRAVITY_FACTOR = 1 < < 18 ,
2016-11-01 23:45:10 +00:00
} ;
2016-10-23 14:14:50 +00:00
enum EnumSimParamInternalSimFlags
{
2018-09-23 21:17:31 +00:00
SIM_PARAM_INTERNAL_CREATE_ROBOT_ASSETS = 1 ,
2016-10-23 14:14:50 +00:00
} ;
2015-07-22 04:46:28 +00:00
///Controlling a robot involves sending the desired state to its joint motor controllers.
///The control mode determines the state variables used for motor control.
2018-01-08 03:24:37 +00:00
struct LoadSoftBodyArgs
2016-11-01 23:45:10 +00:00
{
2018-01-08 03:56:46 +00:00
char m_fileName [ MAX_FILENAME_LENGTH ] ;
2018-09-23 21:17:31 +00:00
double m_scale ;
double m_mass ;
double m_collisionMargin ;
2019-04-25 22:18:25 +00:00
double m_initialPosition [ 3 ] ;
2019-11-27 19:40:10 +00:00
double m_initialOrientation [ 4 ] ;
double m_springElasticStiffness ;
double m_springDampingStiffness ;
2020-05-11 23:42:17 +00:00
int m_dampAllDirections ;
2019-11-27 19:40:10 +00:00
double m_springBendingStiffness ;
double m_corotatedMu ;
double m_corotatedLambda ;
int m_useBendingSprings ;
double m_collisionHardness ;
2020-03-02 21:29:59 +00:00
int m_useSelfCollision ;
2019-11-27 19:40:10 +00:00
double m_frictionCoeff ;
double m_NeoHookeanMu ;
double m_NeoHookeanLambda ;
double m_NeoHookeanDamping ;
2019-11-16 05:25:11 +00:00
int m_useFaceContact ;
2019-11-20 05:01:28 +00:00
char m_simFileName [ MAX_FILENAME_LENGTH ] ;
2020-04-28 00:42:45 +00:00
double m_repulsionStiffness ;
2020-05-26 23:49:52 +00:00
double m_gravFactor ;
2016-11-01 23:45:10 +00:00
} ;
2018-01-08 03:24:37 +00:00
struct b3LoadSoftBodyResultArgs
2018-01-08 03:06:09 +00:00
{
int m_objectUniqueId ;
} ;
2017-03-23 20:54:44 +00:00
struct RequestActualStateArgs
{
int m_bodyUniqueId ;
} ;
2015-06-22 22:30:57 +00:00
2015-06-21 20:24:36 +00:00
struct SendActualStateArgs
{
int m_bodyUniqueId ;
2017-06-16 02:46:27 +00:00
int m_numLinks ;
2015-06-21 20:24:36 +00:00
int m_numDegreeOfFreedomQ ;
int m_numDegreeOfFreedomU ;
2015-07-15 22:23:40 +00:00
2018-09-23 21:17:31 +00:00
double m_rootLocalInertialFrame [ 7 ] ;
2019-03-07 07:27:59 +00:00
struct SendActualStateSharedMemoryStorage * m_stateDetails ;
2015-08-02 21:00:43 +00:00
2019-03-07 07:27:59 +00:00
} ;
struct SendActualStateSharedMemoryStorage
{
2018-09-23 21:17:31 +00:00
//actual state is only written by the server, read-only access by client is expected
double m_actualStateQ [ MAX_DEGREE_OF_FREEDOM ] ;
double m_actualStateQdot [ MAX_DEGREE_OF_FREEDOM ] ;
2016-04-09 01:17:17 +00:00
2018-09-23 21:17:31 +00:00
//measured 6DOF force/torque sensors: force[x,y,z] and torque[x,y,z]
double m_jointReactionForces [ 6 * MAX_DEGREE_OF_FREEDOM ] ;
double m_jointMotorForce [ MAX_DEGREE_OF_FREEDOM ] ;
2019-02-27 17:54:12 +00:00
double m_jointMotorForceMultiDof [ MAX_DEGREE_OF_FREEDOM ] ;
2018-09-23 21:17:31 +00:00
double m_linkState [ 7 * MAX_NUM_LINKS ] ;
double m_linkWorldVelocities [ 6 * MAX_NUM_LINKS ] ; //linear velocity and angular velocity in world space (x/y/z each).
double m_linkLocalInertialFrames [ 7 * MAX_NUM_LINKS ] ;
2017-06-17 01:10:10 +00:00
} ;
struct b3SendCollisionInfoArgs
{
int m_numLinks ;
double m_rootWorldAABBMin [ 3 ] ;
double m_rootWorldAABBMax [ 3 ] ;
2018-09-23 21:17:31 +00:00
double m_linkWorldAABBsMin [ 3 * MAX_NUM_LINKS ] ;
double m_linkWorldAABBsMax [ 3 * MAX_NUM_LINKS ] ;
2015-06-21 20:24:36 +00:00
} ;
2017-06-17 01:10:10 +00:00
struct b3RequestCollisionInfoArgs
{
int m_bodyUniqueId ;
} ;
2015-09-03 21:18:22 +00:00
enum EnumSensorTypes
{
2018-09-23 21:17:31 +00:00
SENSOR_FORCE_TORQUE = 1 ,
SENSOR_IMU = 2 ,
2015-09-03 21:18:22 +00:00
} ;
2015-08-02 21:00:43 +00:00
struct CreateSensorArgs
{
2018-09-23 21:17:31 +00:00
int m_bodyUniqueId ;
int m_numJointSensorChanges ;
int m_sensorType [ MAX_DEGREE_OF_FREEDOM ] ;
///todo: clean up the duplication, make sure no-one else is using those members directly (use C-API header instead)
int m_jointIndex [ MAX_DEGREE_OF_FREEDOM ] ;
int m_enableJointForceSensor [ MAX_DEGREE_OF_FREEDOM ] ;
2015-09-03 21:18:22 +00:00
2018-09-23 21:17:31 +00:00
int m_linkIndex [ MAX_DEGREE_OF_FREEDOM ] ;
int m_enableSensor [ MAX_DEGREE_OF_FREEDOM ] ;
2015-08-02 21:00:43 +00:00
} ;
2015-06-21 20:24:36 +00:00
2018-09-23 21:17:31 +00:00
typedef struct SharedMemoryCommand SharedMemoryCommand_t ;
2015-06-22 22:30:57 +00:00
2015-08-02 21:00:43 +00:00
enum EnumBoxShapeFlags
{
2018-09-23 21:17:31 +00:00
BOX_SHAPE_HAS_INITIAL_POSITION = 1 ,
BOX_SHAPE_HAS_INITIAL_ORIENTATION = 2 ,
BOX_SHAPE_HAS_HALF_EXTENTS = 4 ,
BOX_SHAPE_HAS_MASS = 8 ,
BOX_SHAPE_HAS_COLLISION_SHAPE_TYPE = 16 ,
BOX_SHAPE_HAS_COLOR = 32 ,
2015-08-02 21:00:43 +00:00
} ;
///This command will be replaced to allow arbitrary collision shape types
struct CreateBoxShapeArgs
{
2018-09-23 21:17:31 +00:00
double m_halfExtentsX ;
double m_halfExtentsY ;
double m_halfExtentsZ ;
2015-08-02 21:00:43 +00:00
2015-10-27 21:55:46 +00:00
double m_mass ;
2018-09-23 21:17:31 +00:00
int m_collisionShapeType ; //see SharedMemoryPublic.h
2015-10-27 21:55:46 +00:00
2018-09-23 21:17:31 +00:00
double m_initialPosition [ 3 ] ;
2015-08-02 21:00:43 +00:00
double m_initialOrientation [ 4 ] ;
2015-11-07 01:11:15 +00:00
double m_colorRGBA [ 4 ] ;
2015-08-02 21:00:43 +00:00
} ;
2015-06-21 20:24:36 +00:00
2017-05-04 04:53:29 +00:00
struct b3ObjectArgs
{
2018-09-23 21:17:31 +00:00
int m_numBodies ;
int m_bodyUniqueIds [ MAX_SDF_BODIES ] ;
2017-05-04 04:53:29 +00:00
int m_numUserConstraints ;
int m_userConstraintUniqueIds [ MAX_SDF_BODIES ] ;
2018-09-22 21:18:21 +00:00
int m_numUserCollisionShapes ;
int m_userCollisionShapes [ MAX_SDF_BODIES ] ;
2017-05-04 04:53:29 +00:00
} ;
2017-05-05 00:51:40 +00:00
struct b3Profile
{
char m_name [ MAX_FILENAME_LENGTH ] ;
int m_durationInMicroSeconds ;
2019-08-02 02:12:16 +00:00
int m_type ;
2017-05-05 00:51:40 +00:00
} ;
2016-06-13 17:11:28 +00:00
struct SdfLoadedArgs
{
2018-09-23 21:17:31 +00:00
int m_numBodies ;
int m_bodyUniqueIds [ MAX_SDF_BODIES ] ;
int m_numUserConstraints ;
2017-01-23 03:08:31 +00:00
int m_userConstraintUniqueIds [ MAX_SDF_BODIES ] ;
2016-06-13 17:11:28 +00:00
2018-09-23 21:17:31 +00:00
///@todo(erwincoumans) load cameras, lights etc
//int m_numCameras;
//int m_numLights;
} ;
2016-06-13 17:11:28 +00:00
struct SdfRequestInfoArgs
{
2018-09-23 21:17:31 +00:00
int m_bodyUniqueId ;
2016-06-13 17:11:28 +00:00
} ;
2016-06-27 01:18:30 +00:00
///flags for b3ApplyExternalTorque and b3ApplyExternalForce
enum EnumExternalForcePrivateFlags
{
2018-09-23 21:17:31 +00:00
// EF_LINK_FRAME=1,
// EF_WORLD_FRAME=2,
EF_TORQUE = 4 ,
EF_FORCE = 8 ,
2016-06-27 01:18:30 +00:00
} ;
struct ExternalForceArgs
{
2018-09-23 21:17:31 +00:00
int m_numForcesAndTorques ;
int m_bodyUniqueIds [ MAX_SDF_BODIES ] ;
int m_linkIds [ MAX_SDF_BODIES ] ;
double m_forcesAndTorques [ 3 * MAX_SDF_BODIES ] ;
double m_positions [ 3 * MAX_SDF_BODIES ] ;
int m_forceFlags [ MAX_SDF_BODIES ] ;
2016-06-27 01:18:30 +00:00
} ;
2016-06-13 17:11:28 +00:00
enum EnumSdfRequestInfoFlags
{
2018-09-23 21:17:31 +00:00
SDF_REQUEST_INFO_BODY = 1 ,
//SDF_REQUEST_INFO_CAMERA=2,
2016-06-13 17:11:28 +00:00
} ;
2016-08-10 01:40:12 +00:00
struct CalculateInverseDynamicsArgs
{
int m_bodyUniqueId ;
2018-11-27 16:49:56 +00:00
int m_dofCountQ ;
int m_dofCountQdot ;
2016-08-10 01:40:12 +00:00
double m_jointPositionsQ [ MAX_DEGREE_OF_FREEDOM ] ;
double m_jointVelocitiesQdot [ MAX_DEGREE_OF_FREEDOM ] ;
double m_jointAccelerations [ MAX_DEGREE_OF_FREEDOM ] ;
2019-01-23 05:08:37 +00:00
int m_flags ;
2016-08-10 01:40:12 +00:00
} ;
struct CalculateInverseDynamicsResultArgs
{
int m_bodyUniqueId ;
int m_dofCount ;
double m_jointForces [ MAX_DEGREE_OF_FREEDOM ] ;
} ;
2016-09-07 23:00:38 +00:00
struct CalculateJacobianArgs
{
2018-09-23 21:17:31 +00:00
int m_bodyUniqueId ;
int m_linkIndex ;
double m_localPosition [ 3 ] ;
double m_jointPositionsQ [ MAX_DEGREE_OF_FREEDOM ] ;
double m_jointVelocitiesQdot [ MAX_DEGREE_OF_FREEDOM ] ;
double m_jointAccelerations [ MAX_DEGREE_OF_FREEDOM ] ;
2016-09-07 23:00:38 +00:00
} ;
struct CalculateJacobianResultArgs
{
2018-09-23 21:17:31 +00:00
int m_dofCount ;
double m_linearJacobian [ 3 * MAX_DEGREE_OF_FREEDOM ] ;
double m_angularJacobian [ 3 * MAX_DEGREE_OF_FREEDOM ] ;
2016-09-07 23:00:38 +00:00
} ;
2017-09-30 20:39:11 +00:00
struct CalculateMassMatrixArgs
{
int m_bodyUniqueId ;
double m_jointPositionsQ [ MAX_DEGREE_OF_FREEDOM ] ;
2019-01-23 05:08:37 +00:00
int m_dofCountQ ;
int m_flags ;
2017-09-30 20:39:11 +00:00
} ;
struct CalculateMassMatrixResultArgs
{
int m_dofCount ;
} ;
2018-09-13 02:30:49 +00:00
enum b3EnumCollisionFilterFlags
{
2018-09-23 21:17:31 +00:00
B3_COLLISION_FILTER_PAIR = 1 ,
B3_COLLISION_FILTER_GROUP_MASK = 2 ,
2018-09-13 02:30:49 +00:00
} ;
struct b3CollisionFilterArgs
{
int m_bodyUniqueIdA ;
int m_bodyUniqueIdB ;
int m_linkIndexA ;
int m_linkIndexB ;
int m_enableCollision ;
int m_collisionFilterGroup ;
int m_collisionFilterMask ;
} ;
2016-09-08 22:15:58 +00:00
struct CalculateInverseKinematicsArgs
{
int m_bodyUniqueId ;
2018-09-23 21:17:31 +00:00
// double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM];
2019-07-11 00:21:18 +00:00
double m_targetPositions [ MAX_DEGREE_OF_FREEDOM * 3 ] ;
int m_numEndEffectorLinkIndices ;
2020-07-07 05:57:03 +00:00
double m_targetOrientation [ MAX_DEGREE_OF_FREEDOM * 4 ] ; //orientation represented as quaternion, x,y,z,w
2019-07-11 00:21:18 +00:00
int m_endEffectorLinkIndices [ MAX_DEGREE_OF_FREEDOM ] ;
2018-09-23 21:17:31 +00:00
double m_lowerLimit [ MAX_DEGREE_OF_FREEDOM ] ;
double m_upperLimit [ MAX_DEGREE_OF_FREEDOM ] ;
double m_jointRange [ MAX_DEGREE_OF_FREEDOM ] ;
double m_restPose [ MAX_DEGREE_OF_FREEDOM ] ;
double m_jointDamping [ MAX_DEGREE_OF_FREEDOM ] ;
2018-05-31 23:06:15 +00:00
double m_currentPositions [ MAX_DEGREE_OF_FREEDOM ] ;
int m_maxNumIterations ;
double m_residualThreshold ;
2016-09-08 22:15:58 +00:00
} ;
struct CalculateInverseKinematicsResultArgs
{
int m_bodyUniqueId ;
int m_dofCount ;
double m_jointPositions [ MAX_DEGREE_OF_FREEDOM ] ;
} ;
2016-11-14 22:08:05 +00:00
2017-05-04 04:53:29 +00:00
enum EnumBodyChangeFlags
{
2018-09-23 21:17:31 +00:00
BODY_DELETE_FLAG = 1 ,
2017-05-04 04:53:29 +00:00
} ;
2016-08-23 01:14:29 +00:00
2016-11-14 15:39:34 +00:00
enum EnumUserDebugDrawFlags
{
2018-09-23 21:17:31 +00:00
USER_DEBUG_HAS_LINE = 1 ,
USER_DEBUG_HAS_TEXT = 2 ,
USER_DEBUG_REMOVE_ONE_ITEM = 4 ,
USER_DEBUG_REMOVE_ALL = 8 ,
2016-11-21 15:42:11 +00:00
USER_DEBUG_SET_CUSTOM_OBJECT_COLOR = 16 ,
USER_DEBUG_REMOVE_CUSTOM_OBJECT_COLOR = 32 ,
2018-09-23 21:17:31 +00:00
USER_DEBUG_ADD_PARAMETER = 64 ,
USER_DEBUG_READ_PARAMETER = 128 ,
USER_DEBUG_HAS_OPTION_FLAGS = 256 ,
Improve debug text/line rendering, can be use to draw frames and text in local coordinate of an object / link.
example:
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.getNumJoints(kuka)
pybullet.addUserDebugLine([0,0,0],[0,0,0.1],[0,0,1],trackObjectUniqueId=2,trackLinkIndex=6)
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],trackObjectUniqueId=2,trackLinkIndex=6)
Also allow to render text using a given orientation (instead of pointing to the camera), example:
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textOrientation=[0,0,0,1], trackObjectUniqueId=2,trackLinkIndex=6)
Add drawTexturedTriangleMesh, for drawing 3d text.
Expose readSingleInstanceTransformToCPU, to extract position/orientation from graphics index.
updateTexture: allow to not flip texels around up axis
2017-05-24 05:05:26 +00:00
USER_DEBUG_HAS_TEXT_ORIENTATION = 512 ,
2018-09-23 21:17:31 +00:00
USER_DEBUG_HAS_PARENT_OBJECT = 1024 ,
USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID = 2048 ,
2020-03-17 04:29:30 +00:00
USER_DEBUG_REMOVE_ALL_PARAMETERS = 4096 ,
2016-11-14 15:39:34 +00:00
} ;
struct UserDebugDrawArgs
{
2018-09-23 21:17:31 +00:00
double m_debugLineFromXYZ [ 3 ] ;
double m_debugLineToXYZ [ 3 ] ;
double m_debugLineColorRGB [ 3 ] ;
double m_lineWidth ;
2016-11-14 15:39:34 +00:00
double m_lifeTime ;
2017-01-17 23:42:32 +00:00
int m_itemUniqueId ;
2016-11-14 15:39:34 +00:00
char m_text [ MAX_FILENAME_LENGTH ] ;
double m_textPositionXYZ [ 3 ] ;
Improve debug text/line rendering, can be use to draw frames and text in local coordinate of an object / link.
example:
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.getNumJoints(kuka)
pybullet.addUserDebugLine([0,0,0],[0,0,0.1],[0,0,1],trackObjectUniqueId=2,trackLinkIndex=6)
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],trackObjectUniqueId=2,trackLinkIndex=6)
Also allow to render text using a given orientation (instead of pointing to the camera), example:
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textOrientation=[0,0,0,1], trackObjectUniqueId=2,trackLinkIndex=6)
Add drawTexturedTriangleMesh, for drawing 3d text.
Expose readSingleInstanceTransformToCPU, to extract position/orientation from graphics index.
updateTexture: allow to not flip texels around up axis
2017-05-24 05:05:26 +00:00
double m_textOrientation [ 4 ] ;
2017-05-24 16:06:15 +00:00
int m_parentObjectUniqueId ;
int m_parentLinkIndex ;
2016-11-14 15:39:34 +00:00
double m_textColorRGB [ 3 ] ;
double m_textSize ;
Improve debug text/line rendering, can be use to draw frames and text in local coordinate of an object / link.
example:
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.getNumJoints(kuka)
pybullet.addUserDebugLine([0,0,0],[0,0,0.1],[0,0,1],trackObjectUniqueId=2,trackLinkIndex=6)
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],trackObjectUniqueId=2,trackLinkIndex=6)
Also allow to render text using a given orientation (instead of pointing to the camera), example:
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textOrientation=[0,0,0,1], trackObjectUniqueId=2,trackLinkIndex=6)
Add drawTexturedTriangleMesh, for drawing 3d text.
Expose readSingleInstanceTransformToCPU, to extract position/orientation from graphics index.
updateTexture: allow to not flip texels around up axis
2017-05-24 05:05:26 +00:00
int m_optionFlags ;
2017-10-25 15:15:01 +00:00
int m_replaceItemUniqueId ;
2016-11-21 15:42:11 +00:00
2017-01-17 23:42:32 +00:00
double m_rangeMin ;
double m_rangeMax ;
double m_startValue ;
2016-11-21 15:42:11 +00:00
double m_objectDebugColorRGB [ 3 ] ;
int m_objectUniqueId ;
int m_linkIndex ;
2016-11-14 15:39:34 +00:00
} ;
struct UserDebugDrawResultArgs
{
int m_debugItemUniqueId ;
2017-01-17 23:42:32 +00:00
double m_parameterValue ;
2016-11-14 15:39:34 +00:00
} ;
2017-01-06 01:41:58 +00:00
struct SendVREvents
{
int m_numVRControllerEvents ;
b3VRControllerEvent m_controllerEvents [ MAX_VR_CONTROLLERS ] ;
} ;
2017-03-02 20:33:22 +00:00
struct SendKeyboardEvents
{
int m_numKeyboardEvents ;
b3KeyboardEvent m_keyboardEvents [ MAX_KEYBOARD_EVENTS ] ;
} ;
2017-06-17 20:29:14 +00:00
struct SendMouseEvents
{
int m_numMouseEvents ;
b3MouseEvent m_mouseEvents [ MAX_MOUSE_EVENTS ] ;
} ;
2017-04-08 18:48:12 +00:00
2017-01-06 01:41:58 +00:00
enum eVRCameraEnums
{
2018-09-23 21:17:31 +00:00
VR_CAMERA_ROOT_POSITION = 1 ,
VR_CAMERA_ROOT_ORIENTATION = 2 ,
VR_CAMERA_ROOT_TRACKING_OBJECT = 4 ,
2017-05-18 02:29:12 +00:00
VR_CAMERA_FLAG = 8 ,
2017-01-06 01:41:58 +00:00
} ;
2017-02-17 22:25:53 +00:00
enum eStateLoggingEnums
2017-02-17 18:47:55 +00:00
{
2018-09-23 21:17:31 +00:00
STATE_LOGGING_START_LOG = 1 ,
STATE_LOGGING_STOP_LOG = 2 ,
STATE_LOGGING_FILTER_OBJECT_UNIQUE_ID = 4 ,
STATE_LOGGING_MAX_LOG_DOF = 8 ,
STATE_LOGGING_FILTER_LINK_INDEX_A = 16 ,
STATE_LOGGING_FILTER_LINK_INDEX_B = 32 ,
STATE_LOGGING_FILTER_BODY_UNIQUE_ID_A = 64 ,
STATE_LOGGING_FILTER_BODY_UNIQUE_ID_B = 128 ,
STATE_LOGGING_FILTER_DEVICE_TYPE = 256 ,
STATE_LOGGING_LOG_FLAGS = 512
2017-02-17 18:47:55 +00:00
} ;
2017-01-06 01:41:58 +00:00
struct VRCameraState
{
double m_rootPosition [ 3 ] ;
double m_rootOrientation [ 4 ] ;
int m_trackingObjectUniqueId ;
2017-05-18 02:29:12 +00:00
int m_trackingObjectFlag ;
2017-01-06 01:41:58 +00:00
} ;
2017-02-17 22:25:53 +00:00
struct StateLoggingRequest
{
char m_fileName [ MAX_FILENAME_LENGTH ] ;
2018-09-23 21:17:31 +00:00
int m_logType ; //Minitaur, generic robot, VR states, contact points
int m_numBodyUniqueIds ; ////only if STATE_LOGGING_FILTER_OBJECT_UNIQUE_ID flag is set
2017-02-17 22:25:53 +00:00
int m_bodyUniqueIds [ MAX_SDF_BODIES ] ;
int m_loggingUniqueId ;
2017-03-04 23:30:57 +00:00
int m_maxLogDof ;
2018-09-23 21:17:31 +00:00
int m_linkIndexA ; // only if STATE_LOGGING_FILTER_LINK_INDEX_A flag is set
int m_linkIndexB ; // only if STATE_LOGGING_FILTER_LINK_INDEX_B flag is set
int m_bodyUniqueIdA ; // only if STATE_LOGGING_FILTER_BODY_UNIQUE_ID_A flag is set
int m_bodyUniqueIdB ; // only if STATE_LOGGING_FILTER_BODY_UNIQUE_ID_B flag is set
int m_deviceFilterType ; //user to select (filter) which VR devices to log
2017-08-31 02:41:15 +00:00
int m_logFlags ;
2017-02-17 22:25:53 +00:00
} ;
struct StateLoggingResultArgs
{
int m_loggingUniqueId ;
} ;
2017-02-22 01:36:54 +00:00
enum InternalOpenGLVisualizerUpdateFlags
{
2018-09-23 21:17:31 +00:00
COV_SET_CAMERA_VIEW_MATRIX = 1 ,
COV_SET_FLAGS = 2 ,
2019-06-19 16:01:16 +00:00
COV_SET_LIGHT_POSITION = 4 ,
COV_SET_SHADOWMAP_RESOLUTION = 8 ,
COV_SET_SHADOWMAP_WORLD_SIZE = 16 ,
2019-06-19 16:45:29 +00:00
COV_SET_REMOTE_SYNC_TRANSFORM_INTERVAL = 32 ,
2020-09-07 23:52:14 +00:00
COV_SET_SHADOWMAP_INTENSITY = 64 ,
2017-02-22 01:36:54 +00:00
} ;
struct ConfigureOpenGLVisualizerRequest
{
2018-09-23 21:17:31 +00:00
double m_cameraDistance ;
double m_cameraPitch ;
double m_cameraYaw ;
double m_cameraTargetPosition [ 3 ] ;
2019-06-19 16:01:16 +00:00
double m_lightPosition [ 3 ] ;
int m_shadowMapResolution ;
int m_shadowMapWorldSize ;
2019-06-19 16:45:29 +00:00
double m_remoteSyncTransformInterval ;
2018-09-23 21:17:31 +00:00
int m_setFlag ;
int m_setEnabled ;
2020-09-07 23:52:14 +00:00
double m_shadowMapIntensity ;
2017-02-22 01:36:54 +00:00
} ;
2018-09-23 21:17:31 +00:00
enum
2017-06-03 17:57:56 +00:00
{
URDF_GEOM_HAS_RADIUS = 1 ,
} ;
2017-10-08 01:50:23 +00:00
struct b3CreateUserShapeData
2017-06-03 17:57:56 +00:00
{
2018-09-23 21:17:31 +00:00
int m_type ; //see UrdfGeomTypes
2017-06-03 17:57:56 +00:00
int m_hasChildTransform ;
double m_childPosition [ 3 ] ;
double m_childOrientation [ 4 ] ;
double m_sphereRadius ;
2018-09-23 21:17:31 +00:00
double m_boxHalfExtents [ 3 ] ;
2017-06-03 17:57:56 +00:00
double m_capsuleRadius ;
double m_capsuleHeight ;
2018-09-23 21:17:31 +00:00
int m_hasFromTo ;
2017-06-03 17:57:56 +00:00
double m_capsuleFrom [ 3 ] ;
double m_capsuleTo [ 3 ] ;
double m_planeNormal [ 3 ] ;
2017-06-19 17:14:26 +00:00
double m_planeConstant ;
2017-06-03 17:57:56 +00:00
2018-09-23 21:17:31 +00:00
int m_meshFileType ;
char m_meshFileName [ VISUAL_SHAPE_MAX_PATH_LEN ] ;
double m_meshScale [ 3 ] ;
int m_collisionFlags ;
int m_visualFlags ;
2018-10-26 17:18:51 +00:00
int m_numVertices ;
int m_numIndices ;
2019-01-29 20:03:11 +00:00
int m_numUVs ;
int m_numNormals ;
2019-07-30 03:23:38 +00:00
double m_heightfieldTextureScaling ;
2019-08-11 20:59:24 +00:00
int m_numHeightfieldRows ;
int m_numHeightfieldColumns ;
2018-09-23 21:17:31 +00:00
double m_rgbaColor [ 4 ] ;
double m_specularColor [ 3 ] ;
2019-08-15 04:06:10 +00:00
int m_replaceHeightfieldIndex ;
2017-06-03 17:57:56 +00:00
} ;
2017-06-05 15:01:11 +00:00
# define MAX_COMPOUND_COLLISION_SHAPES 16
2017-06-03 17:57:56 +00:00
2017-10-08 01:50:23 +00:00
struct b3CreateUserShapeArgs
2017-06-03 17:57:56 +00:00
{
2017-10-08 01:50:23 +00:00
int m_numUserShapes ;
b3CreateUserShapeData m_shapes [ MAX_COMPOUND_COLLISION_SHAPES ] ;
2017-06-03 17:57:56 +00:00
} ;
2019-04-12 05:19:02 +00:00
2017-10-08 01:50:23 +00:00
struct b3CreateUserShapeResultArgs
2017-06-03 17:57:56 +00:00
{
2017-10-08 01:50:23 +00:00
int m_userShapeUniqueId ;
2017-06-03 17:57:56 +00:00
} ;
2018-10-22 03:05:29 +00:00
# define MAX_CREATE_MULTI_BODY_LINKS MAX_DEGREE_OF_FREEDOM
2017-06-03 17:57:56 +00:00
enum eCreateMultiBodyEnum
{
2018-09-23 21:17:31 +00:00
MULTI_BODY_HAS_BASE = 1 ,
MULT_BODY_USE_MAXIMAL_COORDINATES = 2 ,
MULT_BODY_HAS_FLAGS = 4 ,
2017-06-03 17:57:56 +00:00
} ;
struct b3CreateMultiBodyArgs
{
char m_bodyName [ 1024 ] ;
int m_baseLinkIndex ;
2018-09-23 21:17:31 +00:00
double m_linkPositions [ 3 * MAX_CREATE_MULTI_BODY_LINKS ] ;
double m_linkOrientations [ 4 * MAX_CREATE_MULTI_BODY_LINKS ] ;
2017-06-03 17:57:56 +00:00
int m_numLinks ;
double m_linkMasses [ MAX_CREATE_MULTI_BODY_LINKS ] ;
2018-09-23 21:17:31 +00:00
double m_linkInertias [ MAX_CREATE_MULTI_BODY_LINKS * 3 ] ;
2017-06-19 17:14:26 +00:00
2018-09-23 21:17:31 +00:00
double m_linkInertialFramePositions [ MAX_CREATE_MULTI_BODY_LINKS * 3 ] ;
double m_linkInertialFrameOrientations [ MAX_CREATE_MULTI_BODY_LINKS * 4 ] ;
2017-06-19 17:14:26 +00:00
2017-06-03 17:57:56 +00:00
int m_linkCollisionShapeUniqueIds [ MAX_CREATE_MULTI_BODY_LINKS ] ;
int m_linkVisualShapeUniqueIds [ MAX_CREATE_MULTI_BODY_LINKS ] ;
2017-06-19 17:14:26 +00:00
int m_linkParentIndices [ MAX_CREATE_MULTI_BODY_LINKS ] ;
int m_linkJointTypes [ MAX_CREATE_MULTI_BODY_LINKS ] ;
2018-09-23 21:17:31 +00:00
double m_linkJointAxis [ 3 * MAX_CREATE_MULTI_BODY_LINKS ] ;
2018-06-02 18:37:14 +00:00
int m_flags ;
2019-02-12 18:36:01 +00:00
int m_numBatchObjects ;
2017-06-03 17:57:56 +00:00
} ;
struct b3CreateMultiBodyResultArgs
{
int m_bodyUniqueId ;
} ;
2017-07-01 02:11:43 +00:00
struct b3ChangeTextureArgs
{
int m_textureUniqueId ;
int m_width ;
int m_height ;
} ;
2017-06-03 17:57:56 +00:00
2017-12-28 18:05:51 +00:00
struct b3StateSerializationArguments
{
char m_fileName [ MAX_URDF_FILENAME_LENGTH ] ;
int m_stateId ;
} ;
2020-01-23 13:46:33 +00:00
struct SyncUserDataRequestArgs
{
// The number of bodies for which we'd like to sync the user data of. When 0, all bodies are synced.
int m_numRequestedBodies ;
// The body IDs for which we'd like to sync the user data of.
int m_requestedBodyIds [ MAX_REQUESTED_BODIES_LENGTH ] ;
} ;
2018-06-02 20:40:08 +00:00
struct SyncUserDataArgs
{
// User data identifiers stored in m_bulletStreamDataServerToClientRefactor
2018-07-03 15:45:19 +00:00
// as as array of integers.
2018-06-02 20:40:08 +00:00
int m_numUserDataIdentifiers ;
2020-02-03 14:24:12 +00:00
// Whether the client should clear its user data cache.
bool m_clearCachedUserDataEntries ;
2018-06-02 20:40:08 +00:00
} ;
2018-09-23 21:17:31 +00:00
struct UserDataRequestArgs
{
int m_userDataId ;
2018-07-03 15:45:19 +00:00
} ;
2018-06-02 20:40:08 +00:00
struct UserDataResponseArgs
{
2018-07-03 15:45:19 +00:00
int m_userDataId ;
2018-07-05 14:01:03 +00:00
int m_bodyUniqueId ;
int m_linkIndex ;
int m_visualShapeIndex ;
2018-06-02 20:40:08 +00:00
int m_valueType ;
int m_valueLength ;
char m_key [ MAX_USER_DATA_KEY_LENGTH ] ;
// Value data stored in m_bulletStreamDataServerToClientRefactor.
} ;
struct AddUserDataRequestArgs
{
int m_bodyUniqueId ;
int m_linkIndex ;
2018-07-05 14:01:03 +00:00
int m_visualShapeIndex ;
2018-06-02 20:40:08 +00:00
int m_valueType ;
int m_valueLength ;
char m_key [ MAX_USER_DATA_KEY_LENGTH ] ;
// Value data stored in m_bulletStreamDataServerToClientRefactor.
} ;
2019-06-18 04:43:38 +00:00
struct b3RequestMeshDataArgs
{
int m_bodyUniqueId ;
int m_linkIndex ;
int m_startingVertex ;
2020-03-17 07:38:12 +00:00
int m_collisionShapeIndex ;
* add textured models of ball.vtk (obj/mtl) and torus (obj/mtl) and cloth.
1) allow to render deformables in 'getCameraImage', for TinyRenderer (tested OK) and EGL (untested)
2) allow to have textures for deformables. See deformable_ball.py, deformable_anchor.py and deformable_torus.py for examples
3) deformables: allow to request simulation mesh data (even if there is a render mesh) See deformable_anchor.py for an example usage
data = p.getMeshData(clothId, -1, flags=p.MESH_DATA_SIMULATION_MESH)
4) fix deletion of deformables, thanks to Fychuyan, https://github.com/bulletphysics/bullet3/pull/3048
5) allow to enable and disable double-sided rendering, p.changeVisualShape(objectUid, linkIndex, flags=p.VISUAL_SHAPE_DOUBLE_SIDED)
6) fix GripperGraspExample, model not found
7) Fix deformable anchor not attaching to multibody with object unique id of 0
8) Fix issue with assignment of unique ids in TinyRenderer/EGL renderer (always use broadphase uid)
9) Avoid crash/issue of simulation with pinned vertices (mass 0) in btDeformableBackwardEulerObjective::applyExplicitForce
10) Store uv/normal in btSoftBody::RenderNode to allow textured meshes
11) (uncomment in btSoftBodyHelpers.cpp): dump vertices and indices in obj wavefront format, when loading a VTK file, for quicker creation of a (textured) surface mesh
12) allow interpolateRenderMesh also for old position-based soft bodies (not only the shiny new FEM deformables)
13) fix a few premake targets
14) update build_visual_studio_vr_pybullet_double_cmake.bat so it suits c:\python37 and installs locally
for local install of Bullet, see also this example https://github.com/erwincoumans/hello_bullet_cmake
2020-09-12 08:03:04 +00:00
int m_flags ;
2019-06-18 00:32:01 +00:00
} ;
2019-06-18 04:43:38 +00:00
struct b3SendMeshDataArgs
{
int m_numVerticesCopied ;
int m_startingVertex ;
int m_numVerticesRemaining ;
2019-06-18 00:32:01 +00:00
} ;
2015-06-21 20:24:36 +00:00
struct SharedMemoryCommand
{
2015-07-23 18:51:25 +00:00
int m_type ;
2018-09-23 21:17:31 +00:00
smUint64_t m_timeStamp ;
int m_sequenceNumber ;
2015-07-31 06:22:44 +00:00
//m_updateFlags is a bit fields to tell which parameters need updating
2018-09-23 21:17:31 +00:00
//for example m_updateFlags = SIM_PARAM_UPDATE_DELTA_TIME | SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS;
int m_updateFlags ;
2015-07-15 22:23:40 +00:00
2018-09-23 21:17:31 +00:00
union {
struct UrdfArgs m_urdfArguments ;
2016-06-04 02:03:56 +00:00
struct SdfArgs m_sdfArguments ;
2018-09-23 21:17:31 +00:00
struct MjcfArgs m_mjcfArguments ;
2016-11-12 02:07:42 +00:00
struct FileArgs m_fileArguments ;
2016-06-13 17:11:28 +00:00
struct SdfRequestInfoArgs m_sdfRequestInfoArgs ;
2017-05-09 17:44:33 +00:00
struct ChangeDynamicsInfoArgs m_changeDynamicsInfoArgs ;
2017-05-09 17:31:28 +00:00
struct GetDynamicsInfoArgs m_getDynamicsInfoArgs ;
2015-07-31 06:22:44 +00:00
struct InitPoseArgs m_initPoseArgs ;
2017-10-05 18:43:14 +00:00
struct b3PhysicsSimulationParameters m_physSimParamArgs ;
2018-09-23 21:17:31 +00:00
struct BulletDataStreamArgs m_dataStreamArguments ;
2015-07-31 06:22:44 +00:00
struct SendDesiredStateArgs m_sendDesiredStateCommandArgument ;
struct RequestActualStateArgs m_requestActualStateInformationCommandArgument ;
2018-09-23 21:17:31 +00:00
struct CreateSensorArgs m_createSensorArguments ;
struct CreateBoxShapeArgs m_createBoxShapeArguments ;
2015-08-20 05:51:16 +00:00
struct RequestDebugLinesArgs m_requestDebugLinesArguments ;
2016-05-31 17:23:04 +00:00
struct RequestPixelDataArgs m_requestPixelDataArguments ;
2015-09-25 05:42:22 +00:00
struct PickBodyArgs m_pickBodyArguments ;
2018-09-23 21:17:31 +00:00
struct ExternalForceArgs m_externalForceArguments ;
2016-08-10 01:40:12 +00:00
struct CalculateInverseDynamicsArgs m_calculateInverseDynamicsArguments ;
2018-09-23 21:17:31 +00:00
struct CalculateJacobianArgs m_calculateJacobianArguments ;
struct CalculateMassMatrixArgs m_calculateMassMatrixArguments ;
struct b3UserConstraint m_userConstraintArguments ;
struct RequestContactDataArgs m_requestContactPointArguments ;
2016-11-10 19:22:22 +00:00
struct RequestOverlappingObjectsArgs m_requestOverlappingObjectsArgs ;
2018-09-23 21:17:31 +00:00
struct RequestVisualShapeDataArgs m_requestVisualShapeDataArguments ;
struct UpdateVisualShapeDataArgs m_updateVisualShapeDataArguments ;
struct LoadTextureArgs m_loadTextureArguments ;
2016-09-08 22:15:58 +00:00
struct CalculateInverseKinematicsArgs m_calculateInverseKinematicsArguments ;
2016-11-14 15:39:34 +00:00
struct UserDebugDrawArgs m_userDebugDrawArgs ;
2016-12-27 03:40:09 +00:00
struct RequestRaycastIntersections m_requestRaycastIntersections ;
2018-09-23 21:17:31 +00:00
struct LoadSoftBodyArgs m_loadSoftBodyArguments ;
2017-01-06 01:41:58 +00:00
struct VRCameraState m_vrCameraStateArguments ;
2017-02-17 22:25:53 +00:00
struct StateLoggingRequest m_stateLoggingArguments ;
2018-09-23 21:17:31 +00:00
struct ConfigureOpenGLVisualizerRequest m_configureOpenGLVisualizerArguments ;
2017-05-04 04:53:29 +00:00
struct b3ObjectArgs m_removeObjectArgs ;
2017-05-05 00:51:40 +00:00
struct b3Profile m_profile ;
2017-10-08 01:50:23 +00:00
struct b3CreateUserShapeArgs m_createUserShapeArgs ;
2017-06-03 17:57:56 +00:00
struct b3CreateMultiBodyArgs m_createMultiBodyArgs ;
2017-06-17 01:10:10 +00:00
struct b3RequestCollisionInfoArgs m_requestCollisionInfoArgs ;
2017-07-01 02:11:43 +00:00
struct b3ChangeTextureArgs m_changeTextureArgs ;
2017-08-28 02:34:00 +00:00
struct b3SearchPathfArgs m_searchPathArgs ;
2017-09-23 02:17:57 +00:00
struct b3CustomCommand m_customCommandArgs ;
2017-12-28 18:05:51 +00:00
struct b3StateSerializationArguments m_loadStateArguments ;
2018-09-23 21:17:31 +00:00
struct RequestCollisionShapeDataArgs m_requestCollisionShapeDataArguments ;
2020-01-23 13:46:33 +00:00
struct SyncUserDataRequestArgs m_syncUserDataRequestArgs ;
2018-07-03 15:45:19 +00:00
struct UserDataRequestArgs m_userDataRequestArgs ;
2018-06-02 20:40:08 +00:00
struct AddUserDataRequestArgs m_addUserDataRequestArgs ;
2018-07-03 15:45:19 +00:00
struct UserDataRequestArgs m_removeUserDataRequestArgs ;
2018-09-13 02:30:49 +00:00
struct b3CollisionFilterArgs m_collisionFilterArgs ;
2019-06-18 04:43:38 +00:00
struct b3RequestMeshDataArgs m_requestMeshDataArgs ;
2018-09-23 21:17:31 +00:00
} ;
2015-06-21 20:24:36 +00:00
} ;
2015-10-27 22:46:13 +00:00
struct RigidBodyCreateArgs
{
2018-09-23 21:17:31 +00:00
int m_bodyUniqueId ;
2015-10-27 22:46:13 +00:00
} ;
2015-07-22 04:46:28 +00:00
2016-09-01 20:30:07 +00:00
struct SendContactDataArgs
{
2018-09-23 21:17:31 +00:00
int m_startingContactPointIndex ;
int m_numContactPointsCopied ;
int m_numRemainingContactPoints ;
2016-09-01 20:30:07 +00:00
} ;
2016-11-10 19:22:22 +00:00
struct SendOverlappingObjectsArgs
{
int m_startingOverlappingObjectIndex ;
int m_numOverlappingObjectsCopied ;
int m_numRemainingOverlappingObjects ;
} ;
2015-07-22 04:46:28 +00:00
struct SharedMemoryStatus
{
int m_type ;
2018-09-23 21:17:31 +00:00
smUint64_t m_timeStamp ;
int m_sequenceNumber ;
2016-11-04 20:15:10 +00:00
//m_streamBytes is only for internal purposes
2018-09-23 21:17:31 +00:00
int m_numDataStreamBytes ;
char * m_dataStream ;
2016-11-04 20:15:10 +00:00
2018-09-23 21:17:31 +00:00
//m_updateFlags is a bit fields to tell which parameters were updated,
2017-01-23 03:08:31 +00:00
//m_updateFlags is ignored for most status messages
2018-09-23 21:17:31 +00:00
int m_updateFlags ;
2017-01-23 03:08:31 +00:00
2018-09-23 21:17:31 +00:00
union {
struct BulletDataStreamArgs m_dataStreamArguments ;
2016-06-13 17:11:28 +00:00
struct SdfLoadedArgs m_sdfLoadedArgs ;
2015-07-23 18:51:25 +00:00
struct SendActualStateArgs m_sendActualStateArgs ;
2015-08-20 05:51:16 +00:00
struct SendDebugLinesArgs m_sendDebugLinesArgs ;
2016-05-31 17:23:04 +00:00
struct SendPixelDataArgs m_sendPixelDataArguments ;
2015-10-27 22:46:13 +00:00
struct RigidBodyCreateArgs m_rigidBodyCreateArgs ;
2016-08-10 01:40:12 +00:00
struct CalculateInverseDynamicsResultArgs m_inverseDynamicsResultArgs ;
2018-09-23 21:17:31 +00:00
struct CalculateJacobianResultArgs m_jacobianResultArgs ;
struct CalculateMassMatrixResultArgs m_massMatrixResultArgs ;
2016-09-01 20:30:07 +00:00
struct SendContactDataArgs m_sendContactPointArgs ;
2016-11-10 19:22:22 +00:00
struct SendOverlappingObjectsArgs m_sendOverlappingObjectsArgs ;
2016-09-08 22:15:58 +00:00
struct CalculateInverseKinematicsResultArgs m_inverseKinematicsResultArgs ;
2016-10-19 05:05:28 +00:00
struct SendVisualShapeDataArgs m_sendVisualShapeArgs ;
2016-11-14 15:39:34 +00:00
struct UserDebugDrawResultArgs m_userDebugDrawArgs ;
2017-01-23 03:08:31 +00:00
struct b3UserConstraint m_userConstraintResultArgs ;
2017-10-19 02:15:35 +00:00
struct b3UserConstraintState m_userConstraintStateResultArgs ;
2016-12-27 03:40:09 +00:00
struct SendVREvents m_sendVREvents ;
2017-03-02 20:33:22 +00:00
struct SendKeyboardEvents m_sendKeyboardEvents ;
2016-12-27 03:40:09 +00:00
struct SendRaycastHits m_raycastHits ;
2017-02-17 22:25:53 +00:00
struct StateLoggingResultArgs m_stateLoggingResultArgs ;
2017-04-10 18:03:41 +00:00
struct b3OpenGLVisualizerCameraInfo m_visualizerCameraResultArgs ;
2017-05-04 04:53:29 +00:00
struct b3ObjectArgs m_removeObjectArgs ;
2017-05-09 17:31:28 +00:00
struct b3DynamicsInfo m_dynamicsInfo ;
2017-10-08 01:50:23 +00:00
struct b3CreateUserShapeResultArgs m_createUserShapeResultArgs ;
2017-06-03 17:57:56 +00:00
struct b3CreateMultiBodyResultArgs m_createMultiBodyResultArgs ;
2017-06-17 01:10:10 +00:00
struct b3SendCollisionInfoArgs m_sendCollisionInfoArgs ;
2017-06-17 20:29:14 +00:00
struct SendMouseEvents m_sendMouseEvents ;
2017-06-30 20:35:07 +00:00
struct b3LoadTextureResultArgs m_loadTextureResultArguments ;
2017-09-23 02:17:57 +00:00
struct b3CustomCommandResultArgs m_customCommandResultArgs ;
2017-10-05 18:43:14 +00:00
struct b3PhysicsSimulationParameters m_simulationParameterResultArgs ;
2017-12-28 18:05:51 +00:00
struct b3StateSerializationArguments m_saveStateResultArgs ;
2018-01-08 03:24:37 +00:00
struct b3LoadSoftBodyResultArgs m_loadSoftBodyResultArguments ;
2018-01-04 03:17:28 +00:00
struct SendCollisionShapeDataArgs m_sendCollisionShapeArgs ;
2018-06-02 20:40:08 +00:00
struct SyncUserDataArgs m_syncUserDataArgs ;
struct UserDataResponseArgs m_userDataResponseArgs ;
2018-07-03 15:45:19 +00:00
struct UserDataRequestArgs m_removeUserDataResponseArgs ;
2019-04-12 05:19:02 +00:00
struct b3ForwardDynamicsAnalyticsArgs m_forwardDynamicsAnalyticsArgs ;
2019-06-18 04:43:38 +00:00
struct b3SendMeshDataArgs m_sendMeshDataArgs ;
2015-07-22 04:46:28 +00:00
} ;
} ;
2018-09-23 21:17:31 +00:00
typedef struct SharedMemoryStatus SharedMemoryStatus_t ;
2015-08-02 21:00:43 +00:00
2018-09-23 21:17:31 +00:00
# endif //SHARED_MEMORY_COMMANDS_H