parent
36943a487a
commit
6a2bb7e3c4
@ -1 +1 @@ |
||||
#version 130 |
||||
#version 330 |
||||
@ -0,0 +1,34 @@ |
||||
libode_la_includedir = $(includedir)/ode
|
||||
libode_la_include_HEADERS = \
|
||||
collision.h \
|
||||
collision_space.h \
|
||||
collision_trimesh.h \
|
||||
common.h \
|
||||
compatibility.h \
|
||||
contact.h \
|
||||
cooperative.h \
|
||||
error.h \
|
||||
export-dif.h \
|
||||
mass.h \
|
||||
matrix.h matrix_coop.h \
|
||||
memory.h \
|
||||
misc.h \
|
||||
objects.h \
|
||||
ode.h \
|
||||
odeconfig.h \
|
||||
odecpp.h \
|
||||
odecpp_collision.h \
|
||||
odeinit.h \
|
||||
odemath.h \
|
||||
odemath_legacy.h \
|
||||
rotation.h \
|
||||
threading.h \
|
||||
threading_impl.h \
|
||||
timer.h
|
||||
|
||||
|
||||
EXTRA_DIST = README precision.h.in version.h.in
|
||||
|
||||
dist_libode_la_include_HEADERS = precision.h version.h
|
||||
|
||||
|
||||
@ -0,0 +1,18 @@ |
||||
|
||||
this is the public C interface to the ODE library. |
||||
|
||||
all these files should be includable from C, i.e. they should not use any |
||||
C++ features. everything should be protected with |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
... |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
the only exceptions are the odecpp.h and odecpp_collisioh.h files, which define a C++ wrapper for |
||||
the C interface. remember to keep this in sync! |
||||
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,182 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001-2003 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_COLLISION_SPACE_H_ |
||||
#define _ODE_COLLISION_SPACE_H_ |
||||
|
||||
#include <ode/common.h> |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
struct dContactGeom; |
||||
|
||||
/**
|
||||
* @brief User callback for geom-geom collision testing. |
||||
* |
||||
* @param data The user data object, as passed to dSpaceCollide. |
||||
* @param o1 The first geom being tested. |
||||
* @param o2 The second geom being test. |
||||
* |
||||
* @remarks The callback function can call dCollide on o1 and o2 to generate |
||||
* contact points between each pair. Then these contact points may be added |
||||
* to the simulation as contact joints. The user's callback function can of |
||||
* course chose not to call dCollide for any pair, e.g. if the user decides |
||||
* that those pairs should not interact. |
||||
* |
||||
* @ingroup collide |
||||
*/ |
||||
typedef void dNearCallback (void *data, dGeomID o1, dGeomID o2); |
||||
|
||||
|
||||
ODE_API dSpaceID dSimpleSpaceCreate (dSpaceID space); |
||||
ODE_API dSpaceID dHashSpaceCreate (dSpaceID space); |
||||
ODE_API dSpaceID dQuadTreeSpaceCreate (dSpaceID space, const dVector3 Center, const dVector3 Extents, int Depth); |
||||
|
||||
|
||||
/* SAP */ |
||||
/* Order XZY or ZXY usually works best, if your Y is up. */ |
||||
#define dSAP_AXES_XYZ ((0)|(1<<2)|(2<<4)) |
||||
#define dSAP_AXES_XZY ((0)|(2<<2)|(1<<4)) |
||||
#define dSAP_AXES_YXZ ((1)|(0<<2)|(2<<4)) |
||||
#define dSAP_AXES_YZX ((1)|(2<<2)|(0<<4)) |
||||
#define dSAP_AXES_ZXY ((2)|(0<<2)|(1<<4)) |
||||
#define dSAP_AXES_ZYX ((2)|(1<<2)|(0<<4)) |
||||
|
||||
ODE_API dSpaceID dSweepAndPruneSpaceCreate( dSpaceID space, int axisorder ); |
||||
|
||||
|
||||
|
||||
ODE_API void dSpaceDestroy (dSpaceID); |
||||
|
||||
ODE_API void dHashSpaceSetLevels (dSpaceID space, int minlevel, int maxlevel); |
||||
ODE_API void dHashSpaceGetLevels (dSpaceID space, int *minlevel, int *maxlevel); |
||||
|
||||
ODE_API void dSpaceSetCleanup (dSpaceID space, int mode); |
||||
ODE_API int dSpaceGetCleanup (dSpaceID space); |
||||
|
||||
/**
|
||||
* @brief Sets sublevel value for a space. |
||||
* |
||||
* Sublevel affects how the space is handled in dSpaceCollide2 when it is collided |
||||
* with another space. If sublevels of both spaces match, the function iterates
|
||||
* geometries of both spaces and collides them with each other. If sublevel of one |
||||
* space is greater than the sublevel of another one, only the geometries of the
|
||||
* space with greater sublevel are iterated, another space is passed into
|
||||
* collision callback as a geometry itself. By default all the spaces are assigned |
||||
* zero sublevel. |
||||
* |
||||
* @note |
||||
* The space sublevel @e IS @e NOT automatically updated when one space is inserted |
||||
* into another or removed from one. It is a client's responsibility to update sublevel |
||||
* value if necessary. |
||||
* |
||||
* @param space the space to modify |
||||
* @param sublevel the sublevel value to be assigned |
||||
* @ingroup collide |
||||
* @see dSpaceGetSublevel |
||||
* @see dSpaceCollide2 |
||||
*/ |
||||
ODE_API void dSpaceSetSublevel (dSpaceID space, int sublevel); |
||||
|
||||
/**
|
||||
* @brief Gets sublevel value of a space. |
||||
* |
||||
* Sublevel affects how the space is handled in dSpaceCollide2 when it is collided |
||||
* with another space. See @c dSpaceSetSublevel for more details. |
||||
* |
||||
* @param space the space to query |
||||
* @returns the sublevel value of the space |
||||
* @ingroup collide |
||||
* @see dSpaceSetSublevel |
||||
* @see dSpaceCollide2 |
||||
*/ |
||||
ODE_API int dSpaceGetSublevel (dSpaceID space); |
||||
|
||||
|
||||
/**
|
||||
* @brief Sets manual cleanup flag for a space. |
||||
* |
||||
* Manual cleanup flag marks a space as eligible for manual thread data cleanup. |
||||
* This function should be called for every space object right after creation in
|
||||
* case if ODE has been initialized with @c dInitFlagManualThreadCleanup flag. |
||||
*
|
||||
* Failure to set manual cleanup flag for a space may lead to some resources
|
||||
* remaining leaked until the program exit. |
||||
* |
||||
* @param space the space to modify |
||||
* @param mode 1 for manual cleanup mode and 0 for default cleanup mode |
||||
* @ingroup collide |
||||
* @see dSpaceGetManualCleanup |
||||
* @see dInitODE2 |
||||
*/ |
||||
ODE_API void dSpaceSetManualCleanup (dSpaceID space, int mode); |
||||
|
||||
/**
|
||||
* @brief Get manual cleanup flag of a space. |
||||
* |
||||
* Manual cleanup flag marks a space space as eligible for manual thread data cleanup. |
||||
* See @c dSpaceSetManualCleanup for more details. |
||||
*
|
||||
* @param space the space to query |
||||
* @returns 1 for manual cleanup mode and 0 for default cleanup mode of the space |
||||
* @ingroup collide |
||||
* @see dSpaceSetManualCleanup |
||||
* @see dInitODE2 |
||||
*/ |
||||
ODE_API int dSpaceGetManualCleanup (dSpaceID space); |
||||
|
||||
ODE_API void dSpaceAdd (dSpaceID, dGeomID); |
||||
ODE_API void dSpaceRemove (dSpaceID, dGeomID); |
||||
ODE_API int dSpaceQuery (dSpaceID, dGeomID); |
||||
ODE_API void dSpaceClean (dSpaceID); |
||||
ODE_API int dSpaceGetNumGeoms (dSpaceID); |
||||
ODE_API dGeomID dSpaceGetGeom (dSpaceID, int i); |
||||
|
||||
/**
|
||||
* @brief Given a space, this returns its class. |
||||
* |
||||
* The ODE classes are: |
||||
* @li dSimpleSpaceClass |
||||
* @li dHashSpaceClass |
||||
* @li dSweepAndPruneSpaceClass |
||||
* @li dQuadTreeSpaceClass |
||||
* @li dFirstUserClass |
||||
* @li dLastUserClass |
||||
* |
||||
* The class id not defined by the user should be between |
||||
* dFirstSpaceClass and dLastSpaceClass. |
||||
* |
||||
* User-defined class will return their own number. |
||||
* |
||||
* @param space the space to query |
||||
* @returns The space class ID. |
||||
* @ingroup collide |
||||
*/ |
||||
ODE_API int dSpaceGetClass(dSpaceID space); |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif |
||||
@ -0,0 +1,316 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001-2003 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
/*
|
||||
* TriMesh code by Erwin de Vries. |
||||
* |
||||
* Trimesh data. |
||||
* This is where the actual vertexdata (pointers), and BV tree is stored. |
||||
* Vertices should be single precision! |
||||
* This should be more sophisticated, so that the user can easyly implement |
||||
* another collision library, but this is a lot of work, and also costs some |
||||
* performance because some data has to be copied. |
||||
*/ |
||||
|
||||
#ifndef _ODE_COLLISION_TRIMESH_H_ |
||||
#define _ODE_COLLISION_TRIMESH_H_ |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/*
|
||||
* Data storage for triangle meshes. |
||||
*/ |
||||
struct dxTriMeshData; |
||||
typedef struct dxTriMeshData* dTriMeshDataID; |
||||
|
||||
|
||||
typedef enum
|
||||
{ |
||||
dMTV__MIN, |
||||
|
||||
dMTV_FIRST = dMTV__MIN, |
||||
dMTV_SECOND, |
||||
dMTV_THIRD, |
||||
|
||||
dMTV__MAX, |
||||
|
||||
} dMeshTriangleVertex; |
||||
|
||||
/*
|
||||
* These don't make much sense now, but they will later when we add more |
||||
* features. |
||||
*/ |
||||
ODE_API dTriMeshDataID dGeomTriMeshDataCreate(void); |
||||
ODE_API void dGeomTriMeshDataDestroy(dTriMeshDataID g); |
||||
|
||||
|
||||
/*
|
||||
* The values of data_id that can be used with dGeomTriMeshDataSet/dGeomTriMeshDataGet |
||||
*/ |
||||
enum
|
||||
{ |
||||
dTRIMESHDATA__MIN, |
||||
|
||||
dTRIMESHDATA_FACE_NORMALS = dTRIMESHDATA__MIN, |
||||
dTRIMESHDATA_USE_FLAGS, |
||||
|
||||
dTRIMESHDATA__MAX, |
||||
|
||||
#ifndef TRIMESH_FACE_NORMALS // Define this name during the header inclusion if you need it for something else
|
||||
// Included for backward compatibility -- please use the corrected name above. Sorry.
|
||||
TRIMESH_FACE_NORMALS = dTRIMESHDATA_FACE_NORMALS, |
||||
#endif |
||||
}; |
||||
|
||||
/*
|
||||
* The flags of the dTRIMESHDATA_USE_FLAGS data elements |
||||
*/ |
||||
enum
|
||||
{ |
||||
dMESHDATAUSE_EDGE1 = 0x01, |
||||
dMESHDATAUSE_EDGE2 = 0x02, |
||||
dMESHDATAUSE_EDGE3 = 0x04, |
||||
dMESHDATAUSE_VERTEX1 = 0x08, |
||||
dMESHDATAUSE_VERTEX2 = 0x10, |
||||
dMESHDATAUSE_VERTEX3 = 0x20, |
||||
}; |
||||
|
||||
/*
|
||||
* Set and get the TriMeshData additional data |
||||
* Note: The data is NOT COPIED on assignment |
||||
*/ |
||||
ODE_API void dGeomTriMeshDataSet(dTriMeshDataID g, int data_id, void *in_data); |
||||
ODE_API void *dGeomTriMeshDataGet(dTriMeshDataID g, int data_id); |
||||
ODE_API void *dGeomTriMeshDataGet2(dTriMeshDataID g, int data_id, dsizeint *pout_size/*=NULL*/); |
||||
|
||||
|
||||
|
||||
/**
|
||||
* We need to set the last transform after each time step for
|
||||
* accurate collision response. These functions get and set that transform. |
||||
* It is stored per geom instance, rather than per dTriMeshDataID. |
||||
*/ |
||||
ODE_API void dGeomTriMeshSetLastTransform( dGeomID g, const dMatrix4 last_trans ); |
||||
ODE_API const dReal* dGeomTriMeshGetLastTransform( dGeomID g ); |
||||
|
||||
/*
|
||||
* Build a TriMesh data object with single precision vertex data. |
||||
*/ |
||||
ODE_API void dGeomTriMeshDataBuildSingle(dTriMeshDataID g, |
||||
const void* Vertices, int VertexStride, int VertexCount,
|
||||
const void* Indices, int IndexCount, int TriStride); |
||||
/* same again with a normals array (used as trimesh-trimesh optimization) */ |
||||
ODE_API void dGeomTriMeshDataBuildSingle1(dTriMeshDataID g, |
||||
const void* Vertices, int VertexStride, int VertexCount,
|
||||
const void* Indices, int IndexCount, int TriStride, |
||||
const void* Normals); |
||||
/*
|
||||
* Build a TriMesh data object with double precision vertex data. |
||||
*/ |
||||
ODE_API void dGeomTriMeshDataBuildDouble(dTriMeshDataID g,
|
||||
const void* Vertices, int VertexStride, int VertexCount,
|
||||
const void* Indices, int IndexCount, int TriStride); |
||||
/* same again with a normals array (used as trimesh-trimesh optimization) */ |
||||
ODE_API void dGeomTriMeshDataBuildDouble1(dTriMeshDataID g,
|
||||
const void* Vertices, int VertexStride, int VertexCount,
|
||||
const void* Indices, int IndexCount, int TriStride, |
||||
const void* Normals); |
||||
|
||||
/*
|
||||
* Simple build. Single/double precision based on dSINGLE/dDOUBLE! |
||||
*/ |
||||
ODE_API void dGeomTriMeshDataBuildSimple(dTriMeshDataID g, |
||||
const dReal* Vertices, int VertexCount, |
||||
const dTriIndex* Indices, int IndexCount); |
||||
/* same again with a normals array (used as trimesh-trimesh optimization) */ |
||||
ODE_API void dGeomTriMeshDataBuildSimple1(dTriMeshDataID g, |
||||
const dReal* Vertices, int VertexCount, |
||||
const dTriIndex* Indices, int IndexCount, |
||||
const int* Normals); |
||||
|
||||
|
||||
/*
|
||||
* Data preprocessing build request flags. |
||||
*/ |
||||
enum |
||||
{ |
||||
dTRIDATAPREPROCESS_BUILD__MIN, |
||||
|
||||
dTRIDATAPREPROCESS_BUILD_CONCAVE_EDGES = dTRIDATAPREPROCESS_BUILD__MIN, // Used to optimize OPCODE trimesh-capsule collisions; allocates 1 byte per triangle; no extra data associated
|
||||
dTRIDATAPREPROCESS_BUILD_FACE_ANGLES, // Used to aid trimesh-convex collisions; memory requirements depend on extra data
|
||||
|
||||
dTRIDATAPREPROCESS_BUILD__MAX, |
||||
}; |
||||
|
||||
/*
|
||||
* Data preprocessing extra values for dTRIDATAPREPROCESS_BUILD_FACE_ANGLES. |
||||
*/ |
||||
enum
|
||||
{ |
||||
dTRIDATAPREPROCESS_FACE_ANGLES_EXTRA__MIN, |
||||
|
||||
dTRIDATAPREPROCESS_FACE_ANGLES_EXTRA_BYTE_POSITIVE = dTRIDATAPREPROCESS_FACE_ANGLES_EXTRA__MIN, // Build angles for convex edges only and store as bytes; allocates 3 bytes per triangle; stores angles (0..180] in 1/254 fractions leaving two values for the flat and all the concaves
|
||||
dTRIDATAPREPROCESS_FACE_ANGLES_EXTRA_BYTE_ALL, // Build angles for all the edges and store in bytes; allocates 3 bytes per triangle; stores angles [-180..0) and (0..180] in 1/127 fractions plus a value for the flat angle
|
||||
dTRIDATAPREPROCESS_FACE_ANGLES_EXTRA_WORD_ALL, // Build angles for all the edges and store in words; allocates 6 bytes per triangle; stores angles [-180..0) and (0..180] in 1/32767 fractions plus a value for the flat angle
|
||||
|
||||
dTRIDATAPREPROCESS_FACE_ANGLES_EXTRA__MAX, |
||||
|
||||
dTRIDATAPREPROCESS_FACE_ANGLES_EXTRA__DEFAULT = dTRIDATAPREPROCESS_FACE_ANGLES_EXTRA_BYTE_POSITIVE, // The default value assumed if the extra data is not provided
|
||||
}; |
||||
|
||||
|
||||
/*
|
||||
* Pre-process the trimesh data according to the request flags. |
||||
* |
||||
* buildRequestFlags is a bitmask of 1U << dTRIDATAPREPROCESS_BUILD_... |
||||
* It is allowed to call the function multiple times provided the bitmasks are different each time. |
||||
* |
||||
* requestExtraData is an optional pointer to array of extra parameters per bitmask bits
|
||||
* (only the elements indexed by positions of raised bits are examined;
|
||||
* defaults are assumed if the pointer is NULL) |
||||
* |
||||
* The function returns a boolean status the only failure reason being insufficient memory. |
||||
*/ |
||||
ODE_API int dGeomTriMeshDataPreprocess2(dTriMeshDataID g, unsigned int buildRequestFlags, const dintptr *requestExtraData/*=NULL | const dintptr (*)[dTRIDATAPREPROCESS_BUILD__MAX]*/); |
||||
|
||||
/*
|
||||
* Obsolete. Equivalent to calling dGeomTriMeshDataPreprocess2(g, (1U << dTRIDATAPREPROCESS_BUILD_CONCAVE_EDGES), NULL) |
||||
*/ |
||||
ODE_API int dGeomTriMeshDataPreprocess(dTriMeshDataID g); |
||||
|
||||
|
||||
|
||||
/*
|
||||
* Get and set the internal preprocessed trimesh data buffer (see the enumerated type above), for loading and saving
|
||||
* These functions are deprecated. Use dGeomTriMeshDataSet/dGeomTriMeshDataGet2 with dTRIMESHDATA_USE_FLAGS instead. |
||||
*/ |
||||
ODE_API_DEPRECATED ODE_API void dGeomTriMeshDataGetBuffer(dTriMeshDataID g, unsigned char** buf, int* bufLen); |
||||
ODE_API_DEPRECATED ODE_API void dGeomTriMeshDataSetBuffer(dTriMeshDataID g, unsigned char* buf); |
||||
|
||||
|
||||
/*
|
||||
* Per triangle callback. Allows the user to say if he wants a collision with |
||||
* a particular triangle. |
||||
*/ |
||||
typedef int dTriCallback(dGeomID TriMesh, dGeomID RefObject, int TriangleIndex); |
||||
ODE_API void dGeomTriMeshSetCallback(dGeomID g, dTriCallback* Callback); |
||||
ODE_API dTriCallback* dGeomTriMeshGetCallback(dGeomID g); |
||||
|
||||
/*
|
||||
* Per object callback. Allows the user to get the list of triangles in 1 |
||||
* shot. Maybe we should remove this one. |
||||
*/ |
||||
typedef void dTriArrayCallback(dGeomID TriMesh, dGeomID RefObject, const int* TriIndices, int TriCount); |
||||
ODE_API void dGeomTriMeshSetArrayCallback(dGeomID g, dTriArrayCallback* ArrayCallback); |
||||
ODE_API dTriArrayCallback* dGeomTriMeshGetArrayCallback(dGeomID g); |
||||
|
||||
/*
|
||||
* Ray callback. |
||||
* Allows the user to say if a ray collides with a triangle on barycentric |
||||
* coords. The user can for example sample a texture with alpha transparency |
||||
* to determine if a collision should occur. |
||||
*/ |
||||
typedef int dTriRayCallback(dGeomID TriMesh, dGeomID Ray, int TriangleIndex, dReal u, dReal v); |
||||
ODE_API void dGeomTriMeshSetRayCallback(dGeomID g, dTriRayCallback* Callback); |
||||
ODE_API dTriRayCallback* dGeomTriMeshGetRayCallback(dGeomID g); |
||||
|
||||
/*
|
||||
* Triangle merging callback. |
||||
* Allows the user to generate a fake triangle index for a new contact generated |
||||
* from merging of two other contacts. That index could later be used by the
|
||||
* user to determine attributes of original triangles used as sources for a
|
||||
* merged contact. |
||||
*/ |
||||
typedef int dTriTriMergeCallback(dGeomID TriMesh, int FirstTriangleIndex, int SecondTriangleIndex); |
||||
ODE_API void dGeomTriMeshSetTriMergeCallback(dGeomID g, dTriTriMergeCallback* Callback); |
||||
ODE_API dTriTriMergeCallback* dGeomTriMeshGetTriMergeCallback(dGeomID g); |
||||
|
||||
/*
|
||||
* Trimesh class |
||||
* Construction. Callbacks are optional. |
||||
*/ |
||||
ODE_API dGeomID dCreateTriMesh(dSpaceID space, dTriMeshDataID Data, dTriCallback* Callback, dTriArrayCallback* ArrayCallback, dTriRayCallback* RayCallback); |
||||
|
||||
ODE_API void dGeomTriMeshSetData(dGeomID g, dTriMeshDataID Data); |
||||
ODE_API dTriMeshDataID dGeomTriMeshGetData(dGeomID g); |
||||
|
||||
|
||||
/* enable/disable/check temporal coherence*/ |
||||
ODE_API void dGeomTriMeshEnableTC(dGeomID g, int geomClass, int enable); |
||||
ODE_API int dGeomTriMeshIsTCEnabled(dGeomID g, int geomClass); |
||||
|
||||
/*
|
||||
* Clears the internal temporal coherence caches. When a geom has its |
||||
* collision checked with a trimesh once, data is stored inside the trimesh. |
||||
* With large worlds with lots of seperate objects this list could get huge. |
||||
* We should be able to do this automagically. |
||||
*/ |
||||
ODE_API void dGeomTriMeshClearTCCache(dGeomID g); |
||||
|
||||
|
||||
/*
|
||||
* returns the TriMeshDataID |
||||
*/ |
||||
ODE_API dTriMeshDataID dGeomTriMeshGetTriMeshDataID(dGeomID g); |
||||
|
||||
/*
|
||||
* Gets a triangle. |
||||
*/ |
||||
ODE_API void dGeomTriMeshGetTriangle(dGeomID g, int Index, dVector3* v0, dVector3* v1, dVector3* v2); |
||||
|
||||
/*
|
||||
* Gets the point on the requested triangle and the given barycentric |
||||
* coordinates. |
||||
*/ |
||||
ODE_API void dGeomTriMeshGetPoint(dGeomID g, int Index, dReal u, dReal v, dVector3 Out); |
||||
|
||||
/*
|
||||
|
||||
This is how the strided data works: |
||||
|
||||
struct StridedVertex{ |
||||
dVector3 Vertex; |
||||
// Userdata
|
||||
}; |
||||
int VertexStride = sizeof(StridedVertex); |
||||
|
||||
struct StridedTri{ |
||||
int Indices[3]; |
||||
// Userdata
|
||||
}; |
||||
int TriStride = sizeof(StridedTri); |
||||
|
||||
*/ |
||||
|
||||
|
||||
ODE_API int dGeomTriMeshGetTriangleCount (dGeomID g); |
||||
|
||||
ODE_API void dGeomTriMeshDataUpdate(dTriMeshDataID g); |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif /* _ODE_COLLISION_TRIMESH_H_ */ |
||||
|
||||
@ -0,0 +1,569 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_COMMON_H_ |
||||
#define _ODE_COMMON_H_ |
||||
|
||||
#include <ode/odeconfig.h> |
||||
#include <ode/error.h> |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
/* configuration stuff */ |
||||
|
||||
/* constants */ |
||||
|
||||
/* pi and 1/sqrt(2) are defined here if necessary because they don't get
|
||||
* defined in <math.h> on some platforms (like MS-Windows) |
||||
*/ |
||||
|
||||
#ifndef M_PI |
||||
#define M_PI REAL(3.1415926535897932384626433832795029) |
||||
#endif |
||||
#ifndef M_PI_2 |
||||
#define M_PI_2 REAL(1.5707963267948966192313216916398) |
||||
#endif |
||||
#ifndef M_SQRT1_2 |
||||
#define M_SQRT1_2 REAL(0.7071067811865475244008443621048490) |
||||
#endif |
||||
|
||||
|
||||
/* floating point data type, vector, matrix and quaternion types */ |
||||
|
||||
#if defined(dSINGLE) |
||||
typedef float dReal; |
||||
#ifdef dDOUBLE |
||||
#error You can only #define dSINGLE or dDOUBLE, not both. |
||||
#endif /* dDOUBLE */ |
||||
#elif defined(dDOUBLE) |
||||
typedef double dReal; |
||||
#else |
||||
#error You must #define dSINGLE or dDOUBLE |
||||
#endif |
||||
|
||||
/* Detect if we've got both trimesh engines enabled. */ |
||||
#if dTRIMESH_ENABLED |
||||
#if dTRIMESH_OPCODE && dTRIMESH_GIMPACT |
||||
#error You can only #define dTRIMESH_OPCODE or dTRIMESH_GIMPACT, not both. |
||||
#endif |
||||
#endif /* dTRIMESH_ENABLED */ |
||||
|
||||
/*
|
||||
* Define a type for indices, either 16 or 32 bit, based on build option |
||||
* TODO: Currently GIMPACT only supports 32 bit indices. |
||||
*/ |
||||
#if dTRIMESH_16BIT_INDICES |
||||
#if dTRIMESH_GIMPACT |
||||
typedef duint32 dTriIndex; |
||||
#else /* dTRIMESH_GIMPACT */ |
||||
typedef duint16 dTriIndex; |
||||
#endif /* dTRIMESH_GIMPACT */ |
||||
#else /* dTRIMESH_16BIT_INDICES */ |
||||
typedef duint32 dTriIndex; |
||||
#endif /* dTRIMESH_16BIT_INDICES */ |
||||
|
||||
/* round an integer up to a multiple of 4, except that 0 and 1 are unmodified
|
||||
* (used to compute matrix leading dimensions) |
||||
*/ |
||||
#define dPAD(a) (((a) > 1) ? (((a) + 3) & (int)(~3)) : (a)) |
||||
|
||||
typedef enum { |
||||
dSA__MIN, |
||||
|
||||
dSA_X = dSA__MIN, |
||||
dSA_Y, |
||||
dSA_Z, |
||||
|
||||
dSA__MAX, |
||||
} dSpaceAxis; |
||||
|
||||
typedef enum { |
||||
dMD__MIN, |
||||
|
||||
dMD_LINEAR = dMD__MIN, |
||||
dMD_ANGULAR, |
||||
|
||||
dMD__MAX, |
||||
} dMotionDynamics; |
||||
|
||||
typedef enum { |
||||
dDA__MIN, |
||||
|
||||
dDA__L_MIN = dDA__MIN + dMD_LINEAR * dSA__MAX, |
||||
|
||||
dDA_LX = dDA__L_MIN + dSA_X, |
||||
dDA_LY = dDA__L_MIN + dSA_Y, |
||||
dDA_LZ = dDA__L_MIN + dSA_Z, |
||||
|
||||
dDA__L_MAX = dDA__L_MIN + dSA__MAX, |
||||
|
||||
dDA__A_MIN = dDA__MIN + dMD_ANGULAR * dSA__MAX, |
||||
|
||||
dDA_AX = dDA__A_MIN + dSA_X, |
||||
dDA_AY = dDA__A_MIN + dSA_Y, |
||||
dDA_AZ = dDA__A_MIN + dSA_Z, |
||||
|
||||
dDA__A_MAX = dDA__A_MIN + dSA__MAX, |
||||
|
||||
dDA__MAX = dDA__MIN + dMD__MAX * dSA__MAX, |
||||
} dDynamicsAxis; |
||||
|
||||
typedef enum { |
||||
dV3E__MIN, |
||||
|
||||
dV3E__AXES_MIN = dV3E__MIN, |
||||
|
||||
dV3E_X = dV3E__AXES_MIN + dSA_X, |
||||
dV3E_Y = dV3E__AXES_MIN + dSA_Y, |
||||
dV3E_Z = dV3E__AXES_MIN + dSA_Z, |
||||
|
||||
dV3E__AXES_MAX = dV3E__AXES_MIN + dSA__MAX, |
||||
|
||||
dV3E_PAD = dV3E__AXES_MAX, |
||||
|
||||
dV3E__MAX, |
||||
|
||||
dV3E__AXES_COUNT = dV3E__AXES_MAX - dV3E__AXES_MIN, |
||||
} dVec3Element; |
||||
|
||||
typedef enum { |
||||
dV4E__MIN, |
||||
|
||||
dV4E_X = dV4E__MIN + dSA_X, |
||||
dV4E_Y = dV4E__MIN + dSA_Y, |
||||
dV4E_Z = dV4E__MIN + dSA_Z, |
||||
dV4E_O = dV4E__MIN + dSA__MAX, |
||||
|
||||
dV4E__MAX, |
||||
} dVec4Element; |
||||
|
||||
typedef enum { |
||||
dM3E__MIN, |
||||
|
||||
dM3E__X_MIN = dM3E__MIN + dSA_X * dV3E__MAX, |
||||
|
||||
dM3E__X_AXES_MIN = dM3E__X_MIN + dV3E__AXES_MIN, |
||||
|
||||
dM3E_XX = dM3E__X_MIN + dV3E_X, |
||||
dM3E_XY = dM3E__X_MIN + dV3E_Y, |
||||
dM3E_XZ = dM3E__X_MIN + dV3E_Z, |
||||
|
||||
dM3E__X_AXES_MAX = dM3E__X_MIN + dV3E__AXES_MAX, |
||||
|
||||
dM3E_XPAD = dM3E__X_MIN + dV3E_PAD, |
||||
|
||||
dM3E__X_MAX = dM3E__X_MIN + dV3E__MAX, |
||||
|
||||
dM3E__Y_MIN = dM3E__MIN + dSA_Y * dV3E__MAX, |
||||
|
||||
dM3E__Y_AXES_MIN = dM3E__Y_MIN + dV3E__AXES_MIN, |
||||
|
||||
dM3E_YX = dM3E__Y_MIN + dV3E_X, |
||||
dM3E_YY = dM3E__Y_MIN + dV3E_Y, |
||||
dM3E_YZ = dM3E__Y_MIN + dV3E_Z, |
||||
|
||||
dM3E__Y_AXES_MAX = dM3E__Y_MIN + dV3E__AXES_MAX, |
||||
|
||||
dM3E_YPAD = dM3E__Y_MIN + dV3E_PAD, |
||||
|
||||
dM3E__Y_MAX = dM3E__Y_MIN + dV3E__MAX, |
||||
|
||||
dM3E__Z_MIN = dM3E__MIN + dSA_Z * dV3E__MAX, |
||||
|
||||
dM3E__Z_AXES_MIN = dM3E__Z_MIN + dV3E__AXES_MIN, |
||||
|
||||
dM3E_ZX = dM3E__Z_MIN + dV3E_X, |
||||
dM3E_ZY = dM3E__Z_MIN + dV3E_Y, |
||||
dM3E_ZZ = dM3E__Z_MIN + dV3E_Z, |
||||
|
||||
dM3E__Z_AXES_MAX = dM3E__Z_MIN + dV3E__AXES_MAX, |
||||
|
||||
dM3E_ZPAD = dM3E__Z_MIN + dV3E_PAD, |
||||
|
||||
dM3E__Z_MAX = dM3E__Z_MIN + dV3E__MAX, |
||||
|
||||
dM3E__MAX = dM3E__MIN + dSA__MAX * dV3E__MAX, |
||||
} dMat3Element; |
||||
|
||||
typedef enum { |
||||
dM4E__MIN, |
||||
|
||||
dM4E__X_MIN = dM4E__MIN + dV4E_X * dV4E__MAX, |
||||
|
||||
dM4E_XX = dM4E__X_MIN + dV4E_X, |
||||
dM4E_XY = dM4E__X_MIN + dV4E_Y, |
||||
dM4E_XZ = dM4E__X_MIN + dV4E_Z, |
||||
dM4E_XO = dM4E__X_MIN + dV4E_O, |
||||
|
||||
dM4E__X_MAX = dM4E__X_MIN + dV4E__MAX, |
||||
|
||||
dM4E__Y_MIN = dM4E__MIN + dV4E_Y * dV4E__MAX, |
||||
|
||||
dM4E_YX = dM4E__Y_MIN + dV4E_X, |
||||
dM4E_YY = dM4E__Y_MIN + dV4E_Y, |
||||
dM4E_YZ = dM4E__Y_MIN + dV4E_Z, |
||||
dM4E_YO = dM4E__Y_MIN + dV4E_O, |
||||
|
||||
dM4E__Y_MAX = dM4E__Y_MIN + dV4E__MAX, |
||||
|
||||
dM4E__Z_MIN = dM4E__MIN + dV4E_Z * dV4E__MAX, |
||||
|
||||
dM4E_ZX = dM4E__Z_MIN + dV4E_X, |
||||
dM4E_ZY = dM4E__Z_MIN + dV4E_Y, |
||||
dM4E_ZZ = dM4E__Z_MIN + dV4E_Z, |
||||
dM4E_ZO = dM4E__Z_MIN + dV4E_O, |
||||
|
||||
dM4E__Z_MAX = dM4E__Z_MIN + dV4E__MAX, |
||||
|
||||
dM4E__O_MIN = dM4E__MIN + dV4E_O * dV4E__MAX, |
||||
|
||||
dM4E_OX = dM4E__O_MIN + dV4E_X, |
||||
dM4E_OY = dM4E__O_MIN + dV4E_Y, |
||||
dM4E_OZ = dM4E__O_MIN + dV4E_Z, |
||||
dM4E_OO = dM4E__O_MIN + dV4E_O, |
||||
|
||||
dM4E__O_MAX = dM4E__O_MIN + dV4E__MAX, |
||||
|
||||
dM4E__MAX = dM4E__MIN + dV4E__MAX * dV4E__MAX, |
||||
} dMat4Element; |
||||
|
||||
typedef enum { |
||||
dQUE__MIN, |
||||
|
||||
dQUE_R = dQUE__MIN, |
||||
|
||||
dQUE__AXIS_MIN, |
||||
|
||||
dQUE_I = dQUE__AXIS_MIN + dSA_X, |
||||
dQUE_J = dQUE__AXIS_MIN + dSA_Y, |
||||
dQUE_K = dQUE__AXIS_MIN + dSA_Z, |
||||
|
||||
dQUE__AXIS_MAX = dQUE__AXIS_MIN + dSA__MAX, |
||||
|
||||
dQUE__MAX = dQUE__AXIS_MAX, |
||||
} dQuatElement; |
||||
|
||||
/* these types are mainly just used in headers */ |
||||
typedef dReal dVector3[dV3E__MAX]; |
||||
typedef dReal dVector4[dV4E__MAX]; |
||||
typedef dReal dMatrix3[dM3E__MAX]; |
||||
typedef dReal dMatrix4[dM4E__MAX]; |
||||
typedef dReal dMatrix6[(dMD__MAX * dV3E__MAX) * (dMD__MAX * dSA__MAX)]; |
||||
typedef dReal dQuaternion[dQUE__MAX]; |
||||
|
||||
|
||||
/* precision dependent scalar math functions */ |
||||
|
||||
#if defined(dSINGLE) |
||||
|
||||
#define REAL(x) (x##f) /* form a constant */ |
||||
#define dRecip(x) ((1.0f/(x))) /* reciprocal */ |
||||
#define dSqrt(x) (sqrtf(x)) /* square root */ |
||||
#define dRecipSqrt(x) ((1.0f/sqrtf(x))) /* reciprocal square root */ |
||||
#define dSin(x) (sinf(x)) /* sine */ |
||||
#define dCos(x) (cosf(x)) /* cosine */ |
||||
#define dFabs(x) (fabsf(x)) /* absolute value */ |
||||
#define dAtan2(y,x) (atan2f(y,x)) /* arc tangent with 2 args */ |
||||
#define dAsin(x) (asinf(x)) |
||||
#define dAcos(x) (acosf(x)) |
||||
#define dFMod(a,b) (fmodf(a,b)) /* modulo */ |
||||
#define dFloor(x) floorf(x) /* floor */ |
||||
#define dCeil(x) ceilf(x) /* ceil */ |
||||
#define dCopySign(a,b) _ode_copysignf(a, b) /* copy value sign */ |
||||
#define dNextAfter(x, y) _ode_nextafterf(x, y) /* next value after */ |
||||
#define dMax(a, b) _ode_fmaxf(a, b) |
||||
#define dMin(a, b) _ode_fminf(a, b) |
||||
|
||||
#ifdef HAVE___ISNANF |
||||
#define dIsNan(x) (__isnanf(x)) |
||||
#elif defined(HAVE__ISNANF) |
||||
#define dIsNan(x) (_isnanf(x)) |
||||
#elif defined(HAVE_ISNANF) |
||||
#define dIsNan(x) (isnanf(x)) |
||||
#else |
||||
/*
|
||||
fall back to _isnan which is the VC way, |
||||
this may seem redundant since we already checked |
||||
for _isnan before, but if isnan is detected by |
||||
configure but is not found during compilation |
||||
we should always make sure we check for __isnanf, |
||||
_isnanf and isnanf in that order before falling |
||||
back to a default |
||||
*/ |
||||
#define dIsNan(x) (_isnan(x)) |
||||
#endif |
||||
|
||||
#elif defined(dDOUBLE) |
||||
|
||||
#define REAL(x) (x) |
||||
#define dRecip(x) (1.0/(x)) |
||||
#define dSqrt(x) sqrt(x) |
||||
#define dRecipSqrt(x) (1.0/sqrt(x)) |
||||
#define dSin(x) sin(x) |
||||
#define dCos(x) cos(x) |
||||
#define dFabs(x) fabs(x) |
||||
#define dAtan2(y,x) atan2((y),(x)) |
||||
#define dAsin(x) asin(x) |
||||
#define dAcos(x) acos(x) |
||||
#define dFMod(a,b) (fmod((a),(b))) |
||||
#define dFloor(x) floor(x) |
||||
#define dCeil(x) ceil(x) |
||||
#define dCopySign(a,b) _ode_copysign(a, b) |
||||
#define dNextAfter(x, y) _ode_nextafter(x, y) |
||||
#define dMax(a, b) _ode_fmax(a, b) |
||||
#define dMin(a, b) _ode_fmin(a, b) |
||||
|
||||
#ifdef HAVE___ISNAN |
||||
#define dIsNan(x) (__isnan(x)) |
||||
#elif defined(HAVE__ISNAN) |
||||
#define dIsNan(x) (_isnan(x)) |
||||
#elif defined(HAVE_ISNAN) |
||||
#define dIsNan(x) (isnan(x)) |
||||
#else |
||||
#define dIsNan(x) (_isnan(x)) |
||||
#endif |
||||
|
||||
#else |
||||
#error You must #define dSINGLE or dDOUBLE |
||||
#endif |
||||
|
||||
|
||||
/* internal object types (all prefixed with `dx') */ |
||||
|
||||
struct dxWorld; /* dynamics world */ |
||||
struct dxSpace; /* collision space */ |
||||
struct dxBody; /* rigid body (dynamics object) */ |
||||
struct dxGeom; /* geometry (collision object) */ |
||||
struct dxJoint; /* joint */ |
||||
struct dxJointGroup;/* joint group */ |
||||
|
||||
|
||||
typedef struct dxWorld *dWorldID; |
||||
typedef struct dxSpace *dSpaceID; |
||||
typedef struct dxBody *dBodyID; |
||||
typedef struct dxGeom *dGeomID; |
||||
typedef struct dxJoint *dJointID; |
||||
typedef struct dxJointGroup *dJointGroupID; |
||||
|
||||
|
||||
/* error numbers */ |
||||
|
||||
enum { |
||||
d_ERR_UNKNOWN = 0, /* unknown error */ |
||||
d_ERR_IASSERT, /* internal assertion failed */ |
||||
d_ERR_UASSERT, /* user assertion failed */ |
||||
d_ERR_LCP /* user assertion failed */ |
||||
}; |
||||
|
||||
|
||||
/* joint type numbers */ |
||||
|
||||
typedef enum { |
||||
dJointTypeNone = 0, /* or "unknown" */ |
||||
dJointTypeBall, |
||||
dJointTypeHinge, |
||||
dJointTypeSlider, |
||||
dJointTypeContact, |
||||
dJointTypeUniversal, |
||||
dJointTypeHinge2, |
||||
dJointTypeFixed, |
||||
dJointTypeNull, |
||||
dJointTypeAMotor, |
||||
dJointTypeLMotor, |
||||
dJointTypePlane2D, |
||||
dJointTypePR, |
||||
dJointTypePU, |
||||
dJointTypePiston, |
||||
dJointTypeDBall, |
||||
dJointTypeDHinge, |
||||
dJointTypeTransmission, |
||||
} dJointType; |
||||
|
||||
|
||||
/* an alternative way of setting joint parameters, using joint parameter
|
||||
* structures and member constants. we don't actually do this yet. |
||||
*/ |
||||
|
||||
/*
|
||||
typedef struct dLimot { |
||||
int mode; |
||||
dReal lostop, histop; |
||||
dReal vel, fmax; |
||||
dReal fudge_factor; |
||||
dReal bounce, soft; |
||||
dReal suspension_erp, suspension_cfm; |
||||
} dLimot; |
||||
|
||||
enum { |
||||
dLimotLoStop = 0x0001, |
||||
dLimotHiStop = 0x0002, |
||||
dLimotVel = 0x0004, |
||||
dLimotFMax = 0x0008, |
||||
dLimotFudgeFactor = 0x0010, |
||||
dLimotBounce = 0x0020, |
||||
dLimotSoft = 0x0040 |
||||
}; |
||||
*/ |
||||
|
||||
|
||||
/* standard joint parameter names. why are these here? - because we don't want
|
||||
* to include all the joint function definitions in joint.cpp. hmmmm. |
||||
* MSVC complains if we call D_ALL_PARAM_NAMES_X with a blank second argument, |
||||
* which is why we have the D_ALL_PARAM_NAMES macro as well. please copy and |
||||
* paste between these two. |
||||
*/ |
||||
|
||||
#define D_ALL_PARAM_NAMES(start) \ |
||||
/* parameters for limits and motors */ \
|
||||
dParamLoStop = start, \
|
||||
dParamHiStop, \
|
||||
dParamVel, \
|
||||
dParamLoVel, \
|
||||
dParamHiVel, \
|
||||
dParamFMax, \
|
||||
dParamFudgeFactor, \
|
||||
dParamBounce, \
|
||||
dParamCFM, \
|
||||
dParamStopERP, \
|
||||
dParamStopCFM, \
|
||||
/* parameters for suspension */ \
|
||||
dParamSuspensionERP, \
|
||||
dParamSuspensionCFM, \
|
||||
dParamERP, \
|
||||
|
||||
/*
|
||||
* \enum D_ALL_PARAM_NAMES_X |
||||
* |
||||
* \var dParamGroup This is the starting value of the different group |
||||
* (i.e. dParamGroup1, dParamGroup2, dParamGroup3) |
||||
* It also helps in the use of parameter |
||||
* (dParamGroup2 | dParamFMax) == dParamFMax2 |
||||
*/ |
||||
#define D_ALL_PARAM_NAMES_X(start,x) \ |
||||
dParamGroup ## x = start, \
|
||||
/* parameters for limits and motors */ \
|
||||
dParamLoStop ## x = start, \
|
||||
dParamHiStop ## x, \
|
||||
dParamVel ## x, \
|
||||
dParamLoVel ## x, \
|
||||
dParamHiVel ## x, \
|
||||
dParamFMax ## x, \
|
||||
dParamFudgeFactor ## x, \
|
||||
dParamBounce ## x, \
|
||||
dParamCFM ## x, \
|
||||
dParamStopERP ## x, \
|
||||
dParamStopCFM ## x, \
|
||||
/* parameters for suspension */ \
|
||||
dParamSuspensionERP ## x, \
|
||||
dParamSuspensionCFM ## x, \
|
||||
dParamERP ## x, |
||||
|
||||
enum { |
||||
D_ALL_PARAM_NAMES(0) |
||||
dParamsInGroup, /* < Number of parameter in a group */ |
||||
D_ALL_PARAM_NAMES_X(0x000,1) |
||||
D_ALL_PARAM_NAMES_X(0x100,2) |
||||
D_ALL_PARAM_NAMES_X(0x200,3) |
||||
|
||||
/* add a multiple of this constant to the basic parameter numbers to get
|
||||
* the parameters for the second, third etc axes. |
||||
*/ |
||||
dParamGroup=0x100 |
||||
}; |
||||
|
||||
|
||||
/* angular motor mode numbers */ |
||||
|
||||
enum { |
||||
dAMotorUser = 0, |
||||
dAMotorEuler = 1 |
||||
}; |
||||
|
||||
/* transmission joint mode numbers */ |
||||
|
||||
enum { |
||||
dTransmissionParallelAxes = 0, |
||||
dTransmissionIntersectingAxes = 1, |
||||
dTransmissionChainDrive = 2 |
||||
}; |
||||
|
||||
|
||||
/* joint force feedback information */ |
||||
|
||||
typedef struct dJointFeedback { |
||||
dVector3 f1; /* force applied to body 1 */ |
||||
dVector3 t1; /* torque applied to body 1 */ |
||||
dVector3 f2; /* force applied to body 2 */ |
||||
dVector3 t2; /* torque applied to body 2 */ |
||||
} dJointFeedback; |
||||
|
||||
|
||||
/* private functions that must be implemented by the collision library:
|
||||
* (1) indicate that a geom has moved, (2) get the next geom in a body list. |
||||
* these functions are called whenever the position of geoms connected to a |
||||
* body have changed, e.g. with dBodySetPosition(), dBodySetRotation(), or |
||||
* when the ODE step function updates the body state. |
||||
*/ |
||||
|
||||
void dGeomMoved (dGeomID); |
||||
dGeomID dGeomGetBodyNext (dGeomID); |
||||
|
||||
/**
|
||||
* dGetConfiguration returns the specific ODE build configuration as |
||||
* a string of tokens. The string can be parsed in a similar way to |
||||
* the OpenGL extension mechanism, the naming convention should be |
||||
* familiar too. The following extensions are reported: |
||||
* |
||||
* ODE |
||||
* ODE_single_precision |
||||
* ODE_double_precision |
||||
* ODE_EXT_no_debug |
||||
* ODE_EXT_trimesh |
||||
* ODE_EXT_opcode |
||||
* ODE_EXT_gimpact |
||||
* ODE_OPC_16bit_indices |
||||
* ODE_OPC_new_collider |
||||
* ODE_EXT_mt_collisions |
||||
* ODE_EXT_threading |
||||
* ODE_THR_builtin_impl |
||||
*/ |
||||
ODE_API const char* dGetConfiguration (void); |
||||
|
||||
/**
|
||||
* Helper to check for a token in the ODE configuration string. |
||||
* Caution, this function is case sensitive. |
||||
* |
||||
* @param token A configuration token, see dGetConfiguration for details |
||||
* |
||||
* @return 1 if exact token is present, 0 if not present |
||||
*/ |
||||
ODE_API int dCheckConfiguration( const char* token ); |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif |
||||
@ -0,0 +1,40 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_COMPATIBILITY_H_ |
||||
#define _ODE_COMPATIBILITY_H_ |
||||
|
||||
/*
|
||||
* ODE's backward compatibility system ensures that as ODE's API |
||||
* evolves, user code will not break. |
||||
*/ |
||||
|
||||
/*
|
||||
* These new rotation function names are more consistent with the |
||||
* rest of the API. |
||||
*/ |
||||
#define dQtoR(q,R) dRfromQ((R),(q)) |
||||
#define dRtoQ(R,q) dQfromR((q),(R)) |
||||
#define dWtoDQ(w,q,dq) dDQfromW((dq),(w),(q)) |
||||
|
||||
|
||||
#endif |
||||
@ -0,0 +1,110 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_CONTACT_H_ |
||||
#define _ODE_CONTACT_H_ |
||||
|
||||
#include <ode/common.h> |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
enum { |
||||
dContactMu2 = 0x001, /**< Use axis dependent friction */ |
||||
dContactAxisDep = 0x001, /**< Same as above */ |
||||
dContactFDir1 = 0x002, /**< Use FDir for the first friction value */ |
||||
dContactBounce = 0x004, /**< Restore collision energy anti-parallel to the normal */ |
||||
dContactSoftERP = 0x008, /**< Don't use global erp for penetration reduction */ |
||||
dContactSoftCFM = 0x010, /**< Don't use global cfm for penetration constraint */ |
||||
dContactMotion1 = 0x020, /**< Use a non-zero target velocity for the constraint */ |
||||
dContactMotion2 = 0x040,
|
||||
dContactMotionN = 0x080,
|
||||
dContactSlip1 = 0x100, /**< Force-dependent slip. */ |
||||
dContactSlip2 = 0x200,
|
||||
dContactRolling = 0x400, /**< Rolling/Angular friction */ |
||||
|
||||
dContactApprox0 = 0x0000, |
||||
dContactApprox1_1 = 0x1000, |
||||
dContactApprox1_2 = 0x2000, |
||||
dContactApprox1_N = 0x4000, /**< For rolling friction */ |
||||
dContactApprox1 = 0x7000 |
||||
}; |
||||
|
||||
|
||||
typedef struct dSurfaceParameters { |
||||
/* must always be defined */ |
||||
int mode; |
||||
dReal mu; |
||||
|
||||
/* only defined if the corresponding flag is set in mode */ |
||||
dReal mu2; |
||||
dReal rho; /**< Rolling friction */ |
||||
dReal rho2; |
||||
dReal rhoN; /**< Spinning friction */ |
||||
dReal bounce; /**< Coefficient of restitution */ |
||||
dReal bounce_vel; /**< Bouncing threshold */ |
||||
dReal soft_erp; |
||||
dReal soft_cfm; |
||||
dReal motion1,motion2,motionN; |
||||
dReal slip1,slip2; |
||||
} dSurfaceParameters; |
||||
|
||||
|
||||
/**
|
||||
* @brief Describe the contact point between two geoms. |
||||
* |
||||
* If two bodies touch, or if a body touches a static feature in its
|
||||
* environment, the contact is represented by one or more "contact |
||||
* points", described by dContactGeom. |
||||
* |
||||
* The convention is that if body 1 is moved along the normal vector by
|
||||
* a distance depth (or equivalently if body 2 is moved the same distance
|
||||
* in the opposite direction) then the contact depth will be reduced to
|
||||
* zero. This means that the normal vector points "in" to body 1. |
||||
* |
||||
* @ingroup collide |
||||
*/ |
||||
typedef struct dContactGeom { |
||||
dVector3 pos; /*< contact position*/ |
||||
dVector3 normal; /*< normal vector*/ |
||||
dReal depth; /*< penetration depth*/ |
||||
dGeomID g1,g2; /*< the colliding geoms*/ |
||||
int side1,side2; /*< (to be documented)*/ |
||||
} dContactGeom; |
||||
|
||||
|
||||
/* contact info used by contact joint */ |
||||
|
||||
typedef struct dContact { |
||||
dSurfaceParameters surface; |
||||
dContactGeom geom; |
||||
dVector3 fdir1; |
||||
} dContact; |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif |
||||
@ -0,0 +1,229 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001-2003 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_COOPERATIVE_H_ |
||||
#define _ODE_COOPERATIVE_H_ |
||||
|
||||
|
||||
#include <ode/common.h> |
||||
#include <ode/threading.h> |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* @defgroup coop Cooperative Algorithms |
||||
* |
||||
* Algorithms implemented as multiple threads doing work cooperatively. |
||||
*/ |
||||
|
||||
|
||||
struct dxCooperative; |
||||
struct dxResourceRequirements; |
||||
struct dxResourceContainer; |
||||
|
||||
/**
|
||||
* @brief A container for cooperative algorithms shared context |
||||
* |
||||
* The Cooperative is a container for cooperative algorithms shared context. |
||||
* At present it contains threading object (either a real one or a defaulted
|
||||
* self-threading). |
||||
* |
||||
* Cooperative use in functions performing computations must be serialized. That is, |
||||
* functions referring to a single instance of Cooperative object must not be called in |
||||
* parallel. |
||||
*/ |
||||
typedef struct dxCooperative *dCooperativeID; |
||||
|
||||
|
||||
/**
|
||||
* @brief A container for resource requirements information |
||||
* |
||||
* The ResourceRequirements object is a container for descriptive information |
||||
* regarding what resources (memory, synchronization objects, etc.) need to be |
||||
* allocated for particular computations. The object can be used for accumulating
|
||||
* resource requirement maxima over multiple functions and then allocating resources |
||||
* that would suffice for any of those function calls. |
||||
* |
||||
* ResourceRequirements objects maintain relations to Cooperative objects since |
||||
* amounts of resources that could be required can depend on characteristics of
|
||||
* shared context, e.g. on maximal number of threads in the threading object. |
||||
* |
||||
* @ingroup coop |
||||
* @see dCooperativeID |
||||
* @see dResourceContainerID |
||||
*/ |
||||
typedef struct dxResourceRequirements *dResourceRequirementsID; |
||||
|
||||
/**
|
||||
* @brief A container for algorithm allocated resources |
||||
*
|
||||
* The ResourceContainer object can contain resources allocated according to information |
||||
* in a ResourceRequirements. The resources inherit link to the threading object
|
||||
* from the requirements they are allocated according to. |
||||
* |
||||
* @ingroup coop |
||||
* @see dResourceRequirementsID |
||||
* @see dCooperativeID |
||||
*/ |
||||
typedef struct dxResourceContainer *dResourceContainerID; |
||||
|
||||
|
||||
/**
|
||||
* @brief Creates a Cooperative object related to the specified threading. |
||||
* |
||||
* NULL's are allowed for the threading. In this case the default (global) self-threading |
||||
* object will be used. |
||||
* |
||||
* Use @c dCooperativeDestroy to destroy the object. The Cooperative object must exist
|
||||
* until after all the objects referencing it are destroyed. |
||||
* |
||||
* @param functionInfo The threading functions to use |
||||
* @param threadingImpl The threading implementation object to use |
||||
* @returns The Cooperative object instance or NULL if allocation fails. |
||||
* @ingroup coop |
||||
* @see dCooperativeDestroy |
||||
*/ |
||||
ODE_API dCooperativeID dCooperativeCreate(const dThreadingFunctionsInfo *functionInfo/*=NULL*/, dThreadingImplementationID threadingImpl/*=NULL*/); |
||||
|
||||
/**
|
||||
* @brief Destroys Cooperative object. |
||||
* |
||||
* The Cooperative object can only be destroyed after all the objects referencing it. |
||||
* |
||||
* @param cooperative A Cooperative object to be deleted (NULL is allowed) |
||||
* @ingroup coop |
||||
* @see dCooperativeCreate |
||||
*/ |
||||
ODE_API void dCooperativeDestroy(dCooperativeID cooperative); |
||||
|
||||
|
||||
/**
|
||||
* @brief Creates a ResourceRequirements object related to a Cooperative. |
||||
* |
||||
* The object is purely descriptive and does not contain any resources by itself. |
||||
* The actual resources are allocated by means of ResourceContainer object. |
||||
* |
||||
* The object is created with empty requirements. It can be then used to accumulate
|
||||
* requirements for one or more function calls and can be cloned or merged with others. |
||||
* The actual requirements information is added to the object by computation related |
||||
* functions. |
||||
* |
||||
* Use @c dResourceRequirementsDestroy to delete the object when it is no longer needed. |
||||
* |
||||
* @param cooperative A Cooperative object to be used |
||||
* @returns The ResourceRequirements object instance or NULL if allocation fails |
||||
* @ingroup coop |
||||
* @see dResourceRequirementsDestroy |
||||
* @see dResourceRequirementsClone |
||||
* @see dResourceRequirementsMergeIn |
||||
* @see dCooperativeCreate |
||||
* @see dResourceContainerAcquire |
||||
*/ |
||||
ODE_API dResourceRequirementsID dResourceRequirementsCreate(dCooperativeID cooperative); |
||||
|
||||
/**
|
||||
* @brief Destroys ResourceRequirements object. |
||||
* |
||||
* The ResourceRequirements object can be destroyed at any time with no regards
|
||||
* to other objects' lifetime. |
||||
* |
||||
* @param requirements A ResourceRequirements object to be deleted (NULL is allowed) |
||||
* @ingroup coop |
||||
* @see dResourceRequirementsCreate |
||||
*/ |
||||
ODE_API void dResourceRequirementsDestroy(dResourceRequirementsID requirements); |
||||
|
||||
/**
|
||||
* @brief Clones ResourceRequirements object. |
||||
* |
||||
* The function creates a copy of the ResourceRequirements object with all the
|
||||
* contents and the relation to Cooperative matching. The object passed in
|
||||
* the parameter is not changed. |
||||
* |
||||
* The object created with the function must later be destroyed with @c dResourceRequirementsDestroy. |
||||
* |
||||
* @param requirements A ResourceRequirements object to be cloned |
||||
* @returns A handle to the new object or NULL if allocation fails |
||||
* @ingroup coop |
||||
* @see dResourceRequirementsCreate |
||||
* @see dResourceRequirementsDestroy |
||||
* @see dResourceRequirementsMergeIn |
||||
*/ |
||||
ODE_API dResourceRequirementsID dResourceRequirementsClone(/*const */dResourceRequirementsID requirements); |
||||
|
||||
/**
|
||||
* @brief Merges one ResourceRequirements object into another ResourceRequirements object. |
||||
* |
||||
* The function updates @a summaryRequirements requirements to be also sufficient |
||||
* for the purposes @a extraRequirements could be used for. The @a extraRequirements |
||||
* object is not changed. The both objects should normally have had been created
|
||||
* with the same Cooperative object. |
||||
* |
||||
* @param summaryRequirements A ResourceRequirements object to be changed |
||||
* @param extraRequirements A ResourceRequirements the requirements to be taken from |
||||
* @ingroup coop |
||||
* @see dResourceRequirementsCreate |
||||
* @see dResourceRequirementsDestroy |
||||
* @see dResourceRequirementsClone |
||||
*/ |
||||
ODE_API void dResourceRequirementsMergeIn(dResourceRequirementsID summaryRequirements, /*const */dResourceRequirementsID extraRequirements); |
||||
|
||||
|
||||
/**
|
||||
* @brief Allocates resources as specified in ResourceRequirements object. |
||||
* |
||||
* The ResourceContainer object can be used in cooperative computation algorithms. |
||||
* |
||||
* The same @a requirements object can be passed to many resource allocations
|
||||
* (with or without modifications) and can be deleted immediately, without waiting |
||||
* for the ResourceContainer object destruction. |
||||
* |
||||
* Use @c dResourceContainerDestroy to delete the object and release the resources
|
||||
* when they are no longer needed. |
||||
* |
||||
* @param requirements The ResourceRequirements object to allocate resources according to |
||||
* @returns A ResourceContainer object instance with the resources allocated or NULL if allocation fails |
||||
* @ingroup coop |
||||
* @see dResourceContainerDestroy |
||||
* @see dResourceRequirementsCreate |
||||
*/ |
||||
ODE_API dResourceContainerID dResourceContainerAcquire(/*const */dResourceRequirementsID requirements); |
||||
|
||||
/**
|
||||
* @brief Destroys ResourceContainer object and releases resources allocated in it. |
||||
* |
||||
* @param resources A ResourceContainer object to be deleted (NULL is allowed) |
||||
* @ingroup coop |
||||
* @see dResourceContainerAcquire |
||||
*/ |
||||
ODE_API void dResourceContainerDestroy(dResourceContainerID resources); |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} // extern "C"
|
||||
#endif |
||||
|
||||
|
||||
#endif // #ifndef _ODE_COOPERATIVE_H_
|
||||
@ -0,0 +1,63 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
/* this comes from the `reuse' library. copy any changes back to the source */ |
||||
|
||||
#ifndef _ODE_ERROR_H_ |
||||
#define _ODE_ERROR_H_ |
||||
|
||||
#include <ode/odeconfig.h> |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* all user defined error functions have this type. error and debug functions
|
||||
* should not return. |
||||
*/ |
||||
typedef void dMessageFunction (int errnum, const char *msg, va_list ap); |
||||
|
||||
/* set a new error, debug or warning handler. if fn is 0, the default handlers
|
||||
* are used. |
||||
*/ |
||||
ODE_API void dSetErrorHandler (dMessageFunction *fn); |
||||
ODE_API void dSetDebugHandler (dMessageFunction *fn); |
||||
ODE_API void dSetMessageHandler (dMessageFunction *fn); |
||||
|
||||
/* return the current error, debug or warning handler. if the return value is
|
||||
* 0, the default handlers are in place. |
||||
*/ |
||||
ODE_API dMessageFunction *dGetErrorHandler(void); |
||||
ODE_API dMessageFunction *dGetDebugHandler(void); |
||||
ODE_API dMessageFunction *dGetMessageHandler(void); |
||||
|
||||
/* generate a fatal error, debug trap or a message. */ |
||||
ODE_API void ODE_NORETURN dError (int num, const char *msg, ...); |
||||
ODE_API void ODE_NORETURN dDebug (int num, const char *msg, ...); |
||||
ODE_API void dMessage (int num, const char *msg, ...); |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif |
||||
@ -0,0 +1,40 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_EXPORT_DIF_ |
||||
#define _ODE_EXPORT_DIF_ |
||||
|
||||
#include <ode/common.h> |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
ODE_API void dWorldExportDIF (dWorldID w, FILE *file, const char *world_name); |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif |
||||
@ -0,0 +1,144 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_MASS_H_ |
||||
#define _ODE_MASS_H_ |
||||
|
||||
#include <ode/common.h> |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
struct dMass; |
||||
typedef struct dMass dMass; |
||||
|
||||
/**
|
||||
* Check if a mass structure has valid value. |
||||
* The function check if the mass and innertia matrix are positive definits |
||||
* |
||||
* @param m A mass structure to check |
||||
* |
||||
* @return 1 if both codition are met |
||||
*/ |
||||
ODE_API int dMassCheck(const dMass *m); |
||||
|
||||
ODE_API void dMassSetZero (dMass *); |
||||
|
||||
ODE_API void dMassSetParameters (dMass *, dReal themass, |
||||
dReal cgx, dReal cgy, dReal cgz, |
||||
dReal I11, dReal I22, dReal I33, |
||||
dReal I12, dReal I13, dReal I23); |
||||
|
||||
ODE_API void dMassSetSphere (dMass *, dReal density, dReal radius); |
||||
ODE_API void dMassSetSphereTotal (dMass *, dReal total_mass, dReal radius); |
||||
|
||||
ODE_API void dMassSetCapsule (dMass *, dReal density, int direction, |
||||
dReal radius, dReal length); |
||||
ODE_API void dMassSetCapsuleTotal (dMass *, dReal total_mass, int direction, |
||||
dReal radius, dReal length); |
||||
|
||||
ODE_API void dMassSetCylinder (dMass *, dReal density, int direction, |
||||
dReal radius, dReal length); |
||||
ODE_API void dMassSetCylinderTotal (dMass *, dReal total_mass, int direction, |
||||
dReal radius, dReal length); |
||||
|
||||
ODE_API void dMassSetBox (dMass *, dReal density, |
||||
dReal lx, dReal ly, dReal lz); |
||||
ODE_API void dMassSetBoxTotal (dMass *, dReal total_mass, |
||||
dReal lx, dReal ly, dReal lz); |
||||
|
||||
ODE_API void dMassSetTrimesh (dMass *, dReal density, dGeomID g); |
||||
|
||||
ODE_API void dMassSetTrimeshTotal (dMass *m, dReal total_mass, dGeomID g); |
||||
|
||||
ODE_API void dMassAdjust (dMass *, dReal newmass); |
||||
|
||||
ODE_API void dMassTranslate (dMass *, dReal x, dReal y, dReal z); |
||||
|
||||
ODE_API void dMassRotate (dMass *, const dMatrix3 R); |
||||
|
||||
ODE_API void dMassAdd (dMass *a, const dMass *b); |
||||
|
||||
|
||||
/* Backwards compatible API */ |
||||
ODE_API_DEPRECATED ODE_API void dMassSetCappedCylinder(dMass *a, dReal b, int c, dReal d, dReal e); |
||||
ODE_API_DEPRECATED ODE_API void dMassSetCappedCylinderTotal(dMass *a, dReal b, int c, dReal d, dReal e); |
||||
|
||||
|
||||
struct dMass { |
||||
dReal mass; |
||||
dVector3 c; |
||||
dMatrix3 I; |
||||
|
||||
#ifdef __cplusplus |
||||
dMass() |
||||
{ dMassSetZero (this); } |
||||
void setZero() |
||||
{ dMassSetZero (this); } |
||||
void setParameters (dReal themass, dReal cgx, dReal cgy, dReal cgz, |
||||
dReal I11, dReal I22, dReal I33, |
||||
dReal I12, dReal I13, dReal I23) |
||||
{ dMassSetParameters (this,themass,cgx,cgy,cgz,I11,I22,I33,I12,I13,I23); } |
||||
|
||||
void setSphere (dReal density, dReal radius) |
||||
{ dMassSetSphere (this,density,radius); } |
||||
void setSphereTotal (dReal total, dReal radius) |
||||
{ dMassSetSphereTotal (this,total,radius); } |
||||
|
||||
void setCapsule (dReal density, int direction, dReal radius, dReal length) |
||||
{ dMassSetCapsule (this,density,direction,radius,length); } |
||||
void setCapsuleTotal (dReal total, int direction, dReal radius, dReal length) |
||||
{ dMassSetCapsule (this,total,direction,radius,length); } |
||||
|
||||
void setCylinder(dReal density, int direction, dReal radius, dReal length) |
||||
{ dMassSetCylinder (this,density,direction,radius,length); } |
||||
void setCylinderTotal(dReal total, int direction, dReal radius, dReal length) |
||||
{ dMassSetCylinderTotal (this,total,direction,radius,length); } |
||||
|
||||
void setBox (dReal density, dReal lx, dReal ly, dReal lz) |
||||
{ dMassSetBox (this,density,lx,ly,lz); } |
||||
void setBoxTotal (dReal total, dReal lx, dReal ly, dReal lz) |
||||
{ dMassSetBoxTotal (this,total,lx,ly,lz); } |
||||
|
||||
void setTrimesh(dReal density, dGeomID g) |
||||
{ dMassSetTrimesh (this, density, g); } |
||||
void setTrimeshTotal(dReal total, dGeomID g) |
||||
{ dMassSetTrimeshTotal (this, total, g); } |
||||
|
||||
void adjust (dReal newmass) |
||||
{ dMassAdjust (this,newmass); } |
||||
void translate (dReal x, dReal y, dReal z) |
||||
{ dMassTranslate (this,x,y,z); } |
||||
void rotate (const dMatrix3 R) |
||||
{ dMassRotate (this,R); } |
||||
void add (const dMass *b) |
||||
{ dMassAdd (this,b); } |
||||
#endif |
||||
}; |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif |
||||
@ -0,0 +1,200 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
/* optimized and unoptimized vector and matrix functions */ |
||||
|
||||
#ifndef _ODE_MATRIX_H_ |
||||
#define _ODE_MATRIX_H_ |
||||
|
||||
#include <ode/common.h> |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
/* set a vector/matrix of size n to all zeros, or to a specific value. */ |
||||
|
||||
ODE_API void dSetZero (dReal *a, int n); |
||||
ODE_API void dSetValue (dReal *a, int n, dReal value); |
||||
|
||||
|
||||
/* get the dot product of two n*1 vectors. if n <= 0 then
|
||||
* zero will be returned (in which case a and b need not be valid). |
||||
*/ |
||||
|
||||
ODE_API dReal dDot (const dReal *a, const dReal *b, int n); |
||||
|
||||
|
||||
/* get the dot products of (a0,b), (a1,b), etc and return them in outsum.
|
||||
* all vectors are n*1. if n <= 0 then zeroes will be returned (in which case |
||||
* the input vectors need not be valid). this function is somewhat faster |
||||
* than calling dDot() for all of the combinations separately. |
||||
*/ |
||||
|
||||
/* NOT INCLUDED in the library for now.
|
||||
void dMultidot2 (const dReal *a0, const dReal *a1, |
||||
const dReal *b, dReal *outsum, int n); |
||||
*/ |
||||
|
||||
|
||||
/* matrix multiplication. all matrices are stored in standard row format.
|
||||
* the digit refers to the argument that is transposed: |
||||
* 0: A = B * C (sizes: A:p*r B:p*q C:q*r) |
||||
* 1: A = B' * C (sizes: A:p*r B:q*p C:q*r) |
||||
* 2: A = B * C' (sizes: A:p*r B:p*q C:r*q) |
||||
* case 1,2 are equivalent to saying that the operation is A=B*C but |
||||
* B or C are stored in standard column format. |
||||
*/ |
||||
|
||||
ODE_API void dMultiply0 (dReal *A, const dReal *B, const dReal *C, int p,int q,int r); |
||||
ODE_API void dMultiply1 (dReal *A, const dReal *B, const dReal *C, int p,int q,int r); |
||||
ODE_API void dMultiply2 (dReal *A, const dReal *B, const dReal *C, int p,int q,int r); |
||||
|
||||
|
||||
/* do an in-place cholesky decomposition on the lower triangle of the n*n
|
||||
* symmetric matrix A (which is stored by rows). the resulting lower triangle |
||||
* will be such that L*L'=A. return 1 on success and 0 on failure (on failure |
||||
* the matrix is not positive definite). |
||||
*/ |
||||
|
||||
ODE_API int dFactorCholesky (dReal *A, int n); |
||||
|
||||
|
||||
/* solve for x: L*L'*x = b, and put the result back into x.
|
||||
* L is size n*n, b is size n*1. only the lower triangle of L is considered. |
||||
*/ |
||||
|
||||
ODE_API void dSolveCholesky (const dReal *L, dReal *b, int n); |
||||
|
||||
|
||||
/* compute the inverse of the n*n positive definite matrix A and put it in
|
||||
* Ainv. this is not especially fast. this returns 1 on success (A was |
||||
* positive definite) or 0 on failure (not PD). |
||||
*/ |
||||
|
||||
ODE_API int dInvertPDMatrix (const dReal *A, dReal *Ainv, int n); |
||||
|
||||
|
||||
/* check whether an n*n matrix A is positive definite, return 1/0 (yes/no).
|
||||
* positive definite means that x'*A*x > 0 for any x. this performs a |
||||
* cholesky decomposition of A. if the decomposition fails then the matrix |
||||
* is not positive definite. A is stored by rows. A is not altered. |
||||
*/ |
||||
|
||||
ODE_API int dIsPositiveDefinite (const dReal *A, int n); |
||||
|
||||
|
||||
/* factorize a matrix A into L*D*L', where L is lower triangular with ones on
|
||||
* the diagonal, and D is diagonal. |
||||
* A is an n*n matrix stored by rows, with a leading dimension of n rounded |
||||
* up to 4. L is written into the strict lower triangle of A (the ones are not |
||||
* written) and the reciprocal of the diagonal elements of D are written into |
||||
* d. |
||||
*/ |
||||
ODE_API void dFactorLDLT (dReal *A, dReal *d, int n, int nskip); |
||||
|
||||
|
||||
/* solve L*x=b, where L is n*n lower triangular with ones on the diagonal,
|
||||
* and x,b are n*1. b is overwritten with x. |
||||
* the leading dimension of L is `nskip'. |
||||
*/ |
||||
ODE_API void dSolveL1 (const dReal *L, dReal *b, int n, int nskip); |
||||
|
||||
|
||||
/* solve L'*x=b, where L is n*n lower triangular with ones on the diagonal,
|
||||
* and x,b are n*1. b is overwritten with x. |
||||
* the leading dimension of L is `nskip'. |
||||
*/ |
||||
ODE_API void dSolveL1T (const dReal *L, dReal *b, int n, int nskip); |
||||
|
||||
|
||||
/* in matlab syntax: a(1:n) = a(1:n) .* d(1:n)
|
||||
*/ |
||||
|
||||
ODE_API void dScaleVector (dReal *a, const dReal *d, int n); |
||||
|
||||
/* The function is an alias for @c dScaleVector.
|
||||
* It has been deprecated because of a wrong naming schema used. |
||||
*/ |
||||
ODE_API_DEPRECATED ODE_API void dVectorScale (dReal *a, const dReal *d, int n); |
||||
|
||||
|
||||
/* given `L', a n*n lower triangular matrix with ones on the diagonal,
|
||||
* and `d', a n*1 vector of the reciprocal diagonal elements of an n*n matrix |
||||
* D, solve L*D*L'*x=b where x,b are n*1. x overwrites b. |
||||
* the leading dimension of L is `nskip'. |
||||
*/ |
||||
|
||||
ODE_API void dSolveLDLT (const dReal *L, const dReal *d, dReal *b, int n, int nskip); |
||||
|
||||
|
||||
/* given an L*D*L' factorization of an n*n matrix A, return the updated
|
||||
* factorization L2*D2*L2' of A plus the following "top left" matrix: |
||||
* |
||||
* [ b a' ] <-- b is a[0] |
||||
* [ a 0 ] <-- a is a[1..n-1] |
||||
* |
||||
* - L has size n*n, its leading dimension is nskip. L is lower triangular |
||||
* with ones on the diagonal. only the lower triangle of L is referenced. |
||||
* - d has size n. d contains the reciprocal diagonal elements of D. |
||||
* - a has size n. |
||||
* the result is written into L, except that the left column of L and d[0] |
||||
* are not actually modified. see ldltaddTL.m for further comments.
|
||||
*/ |
||||
ODE_API void dLDLTAddTL (dReal *L, dReal *d, const dReal *a, int n, int nskip); |
||||
|
||||
|
||||
/* given an L*D*L' factorization of a permuted matrix A, produce a new
|
||||
* factorization for row and column `r' removed. |
||||
* - A has size n1*n1, its leading dimension in nskip. A is symmetric and |
||||
* positive definite. only the lower triangle of A is referenced. |
||||
* A itself may actually be an array of row pointers. |
||||
* - L has size n2*n2, its leading dimension in nskip. L is lower triangular |
||||
* with ones on the diagonal. only the lower triangle of L is referenced. |
||||
* - d has size n2. d contains the reciprocal diagonal elements of D. |
||||
* - p is a permutation vector. it contains n2 indexes into A. each index |
||||
* must be in the range 0..n1-1. |
||||
* - r is the row/column of L to remove. |
||||
* the new L will be written within the old L, i.e. will have the same leading |
||||
* dimension. the last row and column of L, and the last element of d, are |
||||
* undefined on exit. |
||||
* |
||||
* a fast O(n^2) algorithm is used. see ldltremove.m for further comments. |
||||
*/ |
||||
ODE_API void dLDLTRemove (dReal **A, const int *p, dReal *L, dReal *d, |
||||
int n1, int n2, int r, int nskip); |
||||
|
||||
|
||||
/* given an n*n matrix A (with leading dimension nskip), remove the r'th row
|
||||
* and column by moving elements. the new matrix will have the same leading |
||||
* dimension. the last row and column of A are untouched on exit. |
||||
*/ |
||||
ODE_API void dRemoveRowCol (dReal *A, int n, int nskip, int r); |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
|
||||
#endif |
||||
@ -0,0 +1,291 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001-2003 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_MATRIX_COOP_H_ |
||||
#define _ODE_MATRIX_COOP_H_ |
||||
|
||||
|
||||
#include <ode/common.h> |
||||
#include <ode/cooperative.h> |
||||
#include <ode/threading.h> |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* @defgroup matrix_coop Matrix Cooperative Algorithms |
||||
* |
||||
* Cooperative algorithms operating on matrices and vectors. |
||||
* |
||||
* @ingroup coop |
||||
*/ |
||||
|
||||
|
||||
/**
|
||||
* @brief Estimates resource requirements for a @c dCooperativelyFactorLDLT call |
||||
* |
||||
* The function updates the contents of @a requirements to also suffice for calling |
||||
* @c dCooperativelyFactorLDLT with the given parameters.
|
||||
*
|
||||
* Note: The requirements that could have already been in the @a requirements parameter |
||||
* are never decreased. |
||||
*
|
||||
* @param requirements The ResourceRequirements object to update |
||||
* @param maximalAllowedThreadCount Maximal value of allowedThreadCount parameter that is going to be used |
||||
* @param maximalRowCount Maximal value of rowCount parameter that is going to be used |
||||
* @ingroup matrix_coop |
||||
* @see dCooperativelyFactorLDLT |
||||
* @see dResourceRequirementsCreate |
||||
*/ |
||||
ODE_API void dEstimateCooperativelyFactorLDLTResourceRequirements(dResourceRequirementsID requirements, |
||||
unsigned maximalAllowedThreadCount, unsigned maximalRowCount); |
||||
|
||||
/**
|
||||
* @brief Cooperatively factorizes a matrix `A' into L*D*L' |
||||
* |
||||
* The function factorizes a matrix `A' into L*D*L', where `L' is lower triangular with ones on |
||||
* the diagonal, and `D' is diagonal. |
||||
* @a A is a rowCount*rowCount matrix stored by rows, with a leading dimension of @a rowCount rounded |
||||
* up at least to 4 elements. `L; is written into the strict lower triangle of @a A
|
||||
* (the ones are not written) and the reciprocal of the diagonal elements of `D' are written into @a d. |
||||
* |
||||
* The @a resources must have had been allocated from a ResourceRequirements object
|
||||
* estimated in @c dEstimateCooperativelyFactorLDLTResourceRequirements. |
||||
*
|
||||
* The operation is performed cooperatively by up to @a allowedThreadCount threads |
||||
* from thread pool available in @a resources. The threading must must not be simultaneously |
||||
* used (via other @c dResourceContainerID instances) in other calls that employ its features. |
||||
* |
||||
* @param resources The resources allocated for the function |
||||
* @param allowedThreadCount Maximum thread count to use (the actual thread count could be less, depending on other parameters) |
||||
* @param A The `A' matrix |
||||
* @param d The `d' vector |
||||
* @param rowCount The row count in @a A and @a d |
||||
* @param rowskip The actual number of elements to be added to skip to next row in @a A |
||||
* @ingroup matrix_coop |
||||
* @see dEstimateCooperativelyFactorLDLTResourceRequirements |
||||
* @see dResourceContainerAcquire |
||||
* @see dCooperativelySolveLDLT |
||||
*/ |
||||
ODE_API void dCooperativelyFactorLDLT(dResourceContainerID resources, unsigned allowedThreadCount,
|
||||
dReal *A, dReal *d, unsigned rowCount, unsigned rowSkip); |
||||
|
||||
|
||||
/**
|
||||
* @brief Estimates resource requirements for a @c dCooperativelySolveLDLT call |
||||
* |
||||
* The function updates the contents of @a requirements to also suffice for calling |
||||
* @c dCooperativelySolveLDLT with the given parameters.
|
||||
*
|
||||
* Note: The requirements that could have already been in the @a requirements parameter |
||||
* are never decreased. |
||||
*
|
||||
* @param requirements The ResourceRequirements object to update |
||||
* @param maximalAllowedThreadCount Maximal value of allowedThreadCount parameter that is going to be used |
||||
* @param maximalRowCount Maximal value of rowCount parameter that is going to be used |
||||
* @ingroup matrix_coop |
||||
* @see dCooperativelySolveLDLT |
||||
* @see dResourceRequirementsCreate |
||||
*/ |
||||
ODE_API void dEstimateCooperativelySolveLDLTResourceRequirements(dResourceRequirementsID requirements, |
||||
unsigned maximalAllowedThreadCount, unsigned maximalRowCount); |
||||
|
||||
/**
|
||||
* @brief Cooperatively solves L*D*L'*x=b |
||||
*
|
||||
* Given `L', a rowCount*rowCount lower triangular matrix with ones on the diagonal, |
||||
* and `d', a rowCount*1 vector of the reciprocal diagonal elements of a rowCount*rowCount matrix |
||||
* D, the function solves L*D*L'*x=b where `x' and `b' are rowCount*1.
|
||||
* The leading dimension of @a L is @a rowSkip. The resulting vector `x' overwrites @a b. |
||||
* |
||||
* The @a resources must have had been allocated from a ResourceRequirements object
|
||||
* estimated in @c dEstimateCooperativelySolveLDLTResourceRequirements. |
||||
*
|
||||
* The operation is performed cooperatively by up to @a allowedThreadCount threads |
||||
* from thread pool available in @a resources. The threading must must not be simultaneously |
||||
* used (via other @c dResourceContainerID instances) in other calls that employ its features. |
||||
* |
||||
* @param resources The resources allocated for the function |
||||
* @param allowedThreadCount Maximum thread count to use (the actual thread count could be less, depending on other parameters) |
||||
* @param L The `L' matrix |
||||
* @param d The `d' vector |
||||
* @param b The `b' vector; also the result is stored here |
||||
* @param rowCount The row count in @a L, @a d and @a b |
||||
* @param rowskip The actual number of elements to be added to skip to next row in @a L |
||||
* @ingroup matrix_coop |
||||
* @see dEstimateCooperativelySolveLDLTResourceRequirements |
||||
* @see dResourceContainerAcquire |
||||
* @see dCooperativelyFactorLDLT |
||||
*/ |
||||
ODE_API void dCooperativelySolveLDLT(dResourceContainerID resources, unsigned allowedThreadCount,
|
||||
const dReal *L, const dReal *d, dReal *b, unsigned rowCount, unsigned rowSkip); |
||||
|
||||
|
||||
/**
|
||||
* @brief Estimates resource requirements for a @c dCooperativelySolveL1Straight call |
||||
* |
||||
* The function updates the contents of @a requirements to also suffice for calling |
||||
* @c dCooperativelySolveL1Straight with the given parameters.
|
||||
*
|
||||
* Note: The requirements that could have already been in the @a requirements parameter |
||||
* are never decreased. |
||||
*
|
||||
* @param requirements The ResourceRequirements object to update |
||||
* @param maximalAllowedThreadCount Maximal value of allowedThreadCount parameter that is going to be used |
||||
* @param maximalRowCount Maximal value of rowCount parameter that is going to be used |
||||
* @ingroup matrix_coop |
||||
* @see dCooperativelySolveL1Straight |
||||
* @see dResourceRequirementsCreate |
||||
*/ |
||||
ODE_API void dEstimateCooperativelySolveL1StraightResourceRequirements(dResourceRequirementsID requirements, |
||||
unsigned maximalAllowedThreadCount, unsigned maximalRowCount); |
||||
|
||||
/**
|
||||
* @brief Cooperatively solves L*x=b |
||||
*
|
||||
* The function solves L*x=b, where `L' is rowCount*rowCount lower triangular with ones on the diagonal, |
||||
* and `x', `b' are rowCount*1. The leading dimension of @a L is @a rowSkip. |
||||
* @a b is overwritten with `x'. |
||||
* |
||||
* The @a resources must have had been allocated from a ResourceRequirements object
|
||||
* estimated in @c dEstimateCooperativelySolveL1StraightResourceRequirements. |
||||
*
|
||||
* The operation is performed cooperatively by up to @a allowedThreadCount threads |
||||
* from thread pool available in @a resources. The threading must must not be simultaneously |
||||
* used (via other @c dResourceContainerID instances) in other calls that employ its features. |
||||
* |
||||
* @param resources The resources allocated for the function |
||||
* @param allowedThreadCount Maximum thread count to use (the actual thread count could be less, depending on other parameters) |
||||
* @param L The `L' matrix |
||||
* @param b The `b' vector; also the result is stored here |
||||
* @param rowCount The row count in @a L and @a b |
||||
* @param rowskip The actual number of elements to be added to skip to next row in @a L |
||||
* @ingroup matrix_coop |
||||
* @see dEstimateCooperativelySolveL1StraightResourceRequirements |
||||
* @see dResourceContainerAcquire |
||||
* @see dCooperativelyFactorLDLT |
||||
*/ |
||||
ODE_API void dCooperativelySolveL1Straight(dResourceContainerID resources, unsigned allowedThreadCount,
|
||||
const dReal *L, dReal *b, unsigned rowCount, unsigned rowSkip); |
||||
|
||||
|
||||
/**
|
||||
* @brief Estimates resource requirements for a @c dCooperativelySolveL1Transposed call |
||||
* |
||||
* The function updates the contents of @a requirements to also suffice for calling |
||||
* @c dCooperativelySolveL1Transposed with the given parameters.
|
||||
*
|
||||
* Note: The requirements that could have already been in the @a requirements parameter |
||||
* are never decreased. |
||||
*
|
||||
* @param requirements The ResourceRequirements object to update |
||||
* @param maximalAllowedThreadCount Maximal value of allowedThreadCount parameter that is going to be used |
||||
* @param maximalRowCount Maximal value of rowCount parameter that is going to be used |
||||
* @ingroup matrix_coop |
||||
* @see dCooperativelySolveL1Transposed |
||||
* @see dResourceRequirementsCreate |
||||
*/ |
||||
ODE_API void dEstimateCooperativelySolveL1TransposedResourceRequirements(dResourceRequirementsID requirements,
|
||||
unsigned maximalAllowedThreadCount, unsigned maximalRowCount); |
||||
|
||||
/**
|
||||
* @brief Cooperatively solves L'*x=b |
||||
* |
||||
* The function solves L'*x=b, where `L' is rowCount*rowCount lower triangular with ones on the diagonal, |
||||
* and `x', b are rowCount*1. The leading dimension of @a L is @a rowSkip. |
||||
* @a b is overwritten with `x'. |
||||
* |
||||
* The @a resources must have had been allocated from a ResourceRequirements object
|
||||
* estimated in @c dEstimateCooperativelySolveL1TransposedResourceRequirements. |
||||
*
|
||||
* The operation is performed cooperatively by up to @a allowedThreadCount threads |
||||
* from thread pool available in @a resources. The threading must must not be simultaneously |
||||
* used (via other @c dResourceContainerID instances) in other calls that employ its features. |
||||
* |
||||
* @param resources The resources allocated for the function |
||||
* @param allowedThreadCount Maximum thread count to use (the actual thread count could be less, depending on other parameters) |
||||
* @param L The `L' matrix |
||||
* @param b The `b' vector; also the result is stored here |
||||
* @param rowCount The row count in @a L and @a b |
||||
* @param rowskip The actual number of elements to be added to skip to next row in @a L |
||||
* @ingroup matrix_coop |
||||
* @see dEstimateCooperativelySolveL1TransposedResourceRequirements |
||||
* @see dResourceContainerAcquire |
||||
* @see dCooperativelyFactorLDLT |
||||
*/ |
||||
ODE_API void dCooperativelySolveL1Transposed(dResourceContainerID resources, unsigned allowedThreadCount,
|
||||
const dReal *L, dReal *b, unsigned rowCount, unsigned rowSkip); |
||||
|
||||
|
||||
/**
|
||||
* @brief Estimates resource requirements for a @c dCooperativelyScaleVector call |
||||
* |
||||
* The function updates the contents of @a requirements to also suffice for calling |
||||
* @c dCooperativelyScaleVector with the given parameters.
|
||||
*
|
||||
* Note: The requirements that could have already been in the @a requirements parameter |
||||
* are never decreased. |
||||
*
|
||||
* @param requirements The ResourceRequirements object to update |
||||
* @param maximalAllowedThreadCount Maximal value of allowedThreadCount parameter that is going to be used |
||||
* @param maximalElementCount Maximal value of elementCount parameter that is going to be used |
||||
* @ingroup matrix_coop |
||||
* @see dCooperativelyScaleVector |
||||
* @see dResourceRequirementsCreate |
||||
*/ |
||||
ODE_API void dEstimateCooperativelyScaleVectorResourceRequirements(dResourceRequirementsID requirements, |
||||
unsigned maximalAllowedThreadCount, unsigned maximalElementCount); |
||||
|
||||
/**
|
||||
* @brief Multiplies elements of one vector by corresponding element of another one |
||||
*
|
||||
* In matlab syntax, the operation performed is: dataVector(1:elementCount) = dataVector(1:elementCount) .* scaleVector(1:elementCount)
|
||||
* |
||||
* The @a resources must have had been allocated from a ResourceRequirements object
|
||||
* estimated in @c dEstimateCooperativelyScaleVectorResourceRequirements. |
||||
*
|
||||
* The operation is performed cooperatively by up to @a allowedThreadCount threads |
||||
* from thread pool available in @a resources. The threading must must not be simultaneously |
||||
* used (via other @c dResourceContainerID instances) in other calls that employ its features. |
||||
* |
||||
* @param resources The resources allocated for the function |
||||
* @param allowedThreadCount Maximum thread count to use (the actual thread count could be less, depending on other parameters) |
||||
* @param dataVector The vector to be scaled in place |
||||
* @param scaleVector The scale vector |
||||
* @param elementCount The number of elements in @a dataVector and @a scaleVector |
||||
* @ingroup matrix_coop |
||||
* @see dEstimateCooperativelyScaleVectorResourceRequirements |
||||
* @see dResourceContainerAcquire |
||||
* @see dCooperativelyFactorLDLT |
||||
*/ |
||||
ODE_API void dCooperativelyScaleVector(dResourceContainerID resources, unsigned allowedThreadCount,
|
||||
dReal *dataVector, const dReal *scaleVector, unsigned elementCount); |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} // extern "C"
|
||||
#endif |
||||
|
||||
|
||||
#endif // #ifndef _ODE_MATRIX_COOP_H_
|
||||
@ -0,0 +1,59 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
/* this comes from the `reuse' library. copy any changes back to the source */ |
||||
|
||||
#ifndef _ODE_MEMORY_H_ |
||||
#define _ODE_MEMORY_H_ |
||||
|
||||
#include <ode/odeconfig.h> |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* function types to allocate and free memory */ |
||||
typedef void * dAllocFunction (dsizeint size); |
||||
typedef void * dReallocFunction (void *ptr, dsizeint oldsize, dsizeint newsize); |
||||
typedef void dFreeFunction (void *ptr, dsizeint size); |
||||
|
||||
/* set new memory management functions. if fn is 0, the default handlers are
|
||||
* used. */ |
||||
ODE_API void dSetAllocHandler (dAllocFunction *fn); |
||||
ODE_API void dSetReallocHandler (dReallocFunction *fn); |
||||
ODE_API void dSetFreeHandler (dFreeFunction *fn); |
||||
|
||||
/* get current memory management functions */ |
||||
ODE_API dAllocFunction *dGetAllocHandler (void); |
||||
ODE_API dReallocFunction *dGetReallocHandler (void); |
||||
ODE_API dFreeFunction *dGetFreeHandler (void); |
||||
|
||||
/* allocate and free memory. */ |
||||
ODE_API void * dAlloc (dsizeint size); |
||||
ODE_API void * dRealloc (void *ptr, dsizeint oldsize, dsizeint newsize); |
||||
ODE_API void dFree (void *ptr, dsizeint size); |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif |
||||
@ -0,0 +1,86 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
/* miscellaneous math functions. these are mostly useful for testing */ |
||||
|
||||
#ifndef _ODE_MISC_H_ |
||||
#define _ODE_MISC_H_ |
||||
|
||||
#include <ode/common.h> |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
/* return 1 if the random number generator is working. */ |
||||
ODE_API int dTestRand(void); |
||||
|
||||
/* return next 32 bit random number. this uses a not-very-random linear
|
||||
* congruential method. |
||||
*/ |
||||
ODE_API unsigned long dRand(void); |
||||
|
||||
/* get and set the current random number seed. */ |
||||
ODE_API unsigned long dRandGetSeed(void); |
||||
ODE_API void dRandSetSeed (unsigned long s); |
||||
|
||||
/* return a random integer between 0..n-1. the distribution will get worse
|
||||
* as n approaches 2^32. |
||||
*/ |
||||
ODE_API int dRandInt (int n); |
||||
|
||||
/* return a random real number between 0..1 */ |
||||
ODE_API dReal dRandReal(void); |
||||
|
||||
/* print out a matrix */ |
||||
ODE_API void dPrintMatrix (const dReal *A, int n, int m, const char *fmt, FILE *f); |
||||
|
||||
/* make a random vector with entries between +/- range. A has n elements. */ |
||||
ODE_API void dMakeRandomVector (dReal *A, int n, dReal range); |
||||
|
||||
/* make a random matrix with entries between +/- range. A has size n*m. */ |
||||
ODE_API void dMakeRandomMatrix (dReal *A, int n, int m, dReal range); |
||||
|
||||
/* clear the upper triangle of a square matrix */ |
||||
ODE_API void dClearUpperTriangle (dReal *A, int n); |
||||
|
||||
/* return the maximum element difference between the two n*m matrices */ |
||||
ODE_API dReal dMaxDifference (const dReal *A, const dReal *B, int n, int m); |
||||
|
||||
/* return the maximum element difference between the lower triangle of two
|
||||
* n*n matrices */ |
||||
ODE_API dReal dMaxDifferenceLowerTriangle (const dReal *A, const dReal *B, int n); |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
static inline void dPrintMatrix (const dReal *A, int n, int m, const char *fmt="%10.4f ") { dPrintMatrix(A, n, m, fmt, stdout); } |
||||
#endif |
||||
|
||||
|
||||
#endif |
||||
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,56 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_ODE_H_ |
||||
#define _ODE_ODE_H_ |
||||
|
||||
/* include *everything* here */ |
||||
|
||||
#include <ode/odeconfig.h> |
||||
#include <ode/compatibility.h> |
||||
#include <ode/common.h> |
||||
#include <ode/odeinit.h> |
||||
#include <ode/contact.h> |
||||
#include <ode/error.h> |
||||
#include <ode/memory.h> |
||||
#include <ode/odemath.h> |
||||
#include <ode/matrix.h> |
||||
#include <ode/matrix_coop.h> |
||||
#include <ode/timer.h> |
||||
#include <ode/rotation.h> |
||||
#include <ode/mass.h> |
||||
#include <ode/misc.h> |
||||
#include <ode/objects.h> |
||||
#include <ode/collision_space.h> |
||||
#include <ode/collision.h> |
||||
#include <ode/threading.h> |
||||
#include <ode/threading_impl.h> |
||||
#include <ode/cooperative.h> |
||||
#include <ode/export-dif.h> |
||||
#include <ode/version.h> |
||||
|
||||
#ifdef __cplusplus |
||||
# include <ode/odecpp.h> |
||||
# include <ode/odecpp_collision.h> |
||||
#endif |
||||
|
||||
#endif |
||||
@ -0,0 +1,232 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_ODECONFIG_H_ |
||||
#define _ODE_ODECONFIG_H_ |
||||
|
||||
/* Pull in the standard headers */ |
||||
#include <stddef.h> |
||||
#include <limits.h> |
||||
#include <stdio.h> |
||||
#include <stdlib.h> |
||||
#include <stdarg.h> |
||||
#include <math.h> |
||||
#include <string.h> |
||||
#include <float.h> |
||||
|
||||
|
||||
#include <ode/precision.h> |
||||
|
||||
|
||||
#if defined(ODE_DLL) || defined(ODE_LIB) |
||||
#define __ODE__ |
||||
#endif |
||||
|
||||
/* Define a DLL export symbol for those platforms that need it */ |
||||
#if defined(_MSC_VER) || (defined(__GNUC__) && defined(_WIN32)) |
||||
#if defined(ODE_DLL) |
||||
#define ODE_API __declspec(dllexport) |
||||
#else |
||||
#define ODE_API |
||||
#endif |
||||
#endif |
||||
|
||||
#if !defined(ODE_API) |
||||
#define ODE_API |
||||
#endif |
||||
|
||||
#if defined(_MSC_VER) |
||||
# define ODE_API_DEPRECATED __declspec(deprecated) |
||||
#elif defined (__GNUC__) && ( (__GNUC__ > 3) || ((__GNUC__ == 3) && (__GNUC_MINOR__ >= 1)) ) |
||||
# define ODE_API_DEPRECATED __attribute__((__deprecated__)) |
||||
#else |
||||
# define ODE_API_DEPRECATED |
||||
#endif |
||||
|
||||
#define ODE_PURE_INLINE static __inline |
||||
#define ODE_INLINE __inline |
||||
|
||||
#if defined(__cplusplus) |
||||
#define ODE_EXTERN_C extern "C" |
||||
#else |
||||
#define ODE_EXTERN_C |
||||
#endif |
||||
|
||||
#if defined(__GNUC__) |
||||
#define ODE_NORETURN __attribute__((noreturn)) |
||||
#elif defined(_MSC_VER) |
||||
#define ODE_NORETURN __declspec(noreturn) |
||||
#else // #if !defined(_MSC_VER)
|
||||
#define ODE_NORETURN |
||||
#endif // #if !defined(__GNUC__)
|
||||
|
||||
|
||||
/* Well-defined common data types...need to be defined for 64 bit systems */ |
||||
#if defined(__aarch64__) || defined(__alpha__) || defined(__ppc64__) \ |
||||
|| defined(__s390__) || defined(__s390x__) || defined(__zarch__) \
|
||||
|| defined(__mips__) || defined(__powerpc64__) || defined(__riscv) \
|
||||
|| (defined(__sparc__) && defined(__arch64__)) |
||||
#include <stdint.h> |
||||
typedef int64_t dint64; |
||||
typedef uint64_t duint64; |
||||
typedef int32_t dint32; |
||||
typedef uint32_t duint32; |
||||
typedef int16_t dint16; |
||||
typedef uint16_t duint16; |
||||
typedef int8_t dint8; |
||||
typedef uint8_t duint8; |
||||
|
||||
typedef intptr_t dintptr; |
||||
typedef uintptr_t duintptr; |
||||
typedef ptrdiff_t ddiffint; |
||||
typedef size_t dsizeint; |
||||
|
||||
#elif (defined(_M_IA64) || defined(__ia64__) || defined(_M_AMD64) || defined(__x86_64__)) && !defined(__ILP32__) && !defined(_ILP32) |
||||
#define X86_64_SYSTEM 1 |
||||
#if defined(_MSC_VER) |
||||
typedef __int64 dint64; |
||||
typedef unsigned __int64 duint64; |
||||
#else |
||||
#if defined(_LP64) || defined(__LP64__) |
||||
typedef long dint64; |
||||
typedef unsigned long duint64; |
||||
#else |
||||
typedef long long dint64; |
||||
typedef unsigned long long duint64; |
||||
#endif |
||||
#endif |
||||
typedef int dint32; |
||||
typedef unsigned int duint32; |
||||
typedef short dint16; |
||||
typedef unsigned short duint16; |
||||
typedef signed char dint8; |
||||
typedef unsigned char duint8; |
||||
|
||||
typedef dint64 dintptr; |
||||
typedef duint64 duintptr; |
||||
typedef dint64 ddiffint; |
||||
typedef duint64 dsizeint; |
||||
|
||||
#else |
||||
#if defined(_MSC_VER) |
||||
typedef __int64 dint64; |
||||
typedef unsigned __int64 duint64; |
||||
#else |
||||
typedef long long dint64; |
||||
typedef unsigned long long duint64; |
||||
#endif |
||||
typedef int dint32; |
||||
typedef unsigned int duint32; |
||||
typedef short dint16; |
||||
typedef unsigned short duint16; |
||||
typedef signed char dint8; |
||||
typedef unsigned char duint8; |
||||
|
||||
typedef dint32 dintptr; |
||||
typedef duint32 duintptr; |
||||
typedef dint32 ddiffint; |
||||
typedef duint32 dsizeint; |
||||
|
||||
#endif |
||||
|
||||
|
||||
/* Define the dInfinity macro */ |
||||
#ifdef INFINITY |
||||
#ifdef dSINGLE |
||||
#define dInfinity ((float)INFINITY) |
||||
#else |
||||
#define dInfinity ((double)INFINITY) |
||||
#endif |
||||
#elif defined(HUGE_VAL) |
||||
#ifdef dSINGLE |
||||
#ifdef HUGE_VALF |
||||
#define dInfinity HUGE_VALF |
||||
#else |
||||
#define dInfinity ((float)HUGE_VAL) |
||||
#endif |
||||
#else |
||||
#define dInfinity HUGE_VAL |
||||
#endif |
||||
#else |
||||
#ifdef dSINGLE |
||||
#define dInfinity ((float)(1.0/0.0)) |
||||
#else |
||||
#define dInfinity (1.0/0.0) |
||||
#endif |
||||
#endif |
||||
|
||||
|
||||
/* Define the dNaN macro */ |
||||
#if defined(NAN) |
||||
#define dNaN NAN |
||||
#elif defined(__GNUC__) |
||||
#define dNaN ({ union { duint32 m_ui; float m_f; } un; un.m_ui = 0x7FC00000; un.m_f; }) |
||||
#elif defined(__cplusplus) |
||||
union _dNaNUnion |
||||
{ |
||||
_dNaNUnion(): m_ui(0x7FC00000) {} |
||||
duint32 m_ui;
|
||||
float m_f; |
||||
}; |
||||
#define dNaN (_dNaNUnion().m_f) |
||||
#else |
||||
#ifdef dSINGLE |
||||
#define dNaN ((float)(dInfinity - dInfinity)) |
||||
#else |
||||
#define dNaN (dInfinity - dInfinity) |
||||
#endif |
||||
#endif |
||||
|
||||
|
||||
/* Visual C does not define these functions */ |
||||
#if defined(_MSC_VER) |
||||
#define _ode_copysignf(x, y) ((float)_copysign(x, y)) |
||||
#define _ode_copysign(x, y) _copysign(x, y) |
||||
#define _ode_nextafterf(x, y) _nextafterf(x, y) |
||||
#define _ode_nextafter(x, y) _nextafter(x, y) |
||||
#if !defined(_WIN64) && defined(dSINGLE) |
||||
#define _ODE__NEXTAFTERF_REQUIRED |
||||
ODE_EXTERN_C float _nextafterf(float x, float y); |
||||
#endif |
||||
#else |
||||
#define _ode_copysignf(x, y) copysignf(x, y) |
||||
#define _ode_copysign(x, y) copysign(x, y) |
||||
#define _ode_nextafterf(x, y) nextafterf(x, y) |
||||
#define _ode_nextafter(x, y) nextafter(x, y) |
||||
#endif |
||||
|
||||
|
||||
#if defined(_MSC_VER) && _MSC_VER < 1700 // Also mind similar defines in ccd/vec3.h
|
||||
/* Define fmin, fmax, fminf, fmaxf which are missing from MSVC (up to VS2008 at least) */ |
||||
static __inline double _ode_fmin(double x, double y) { return __min(x, y); } |
||||
static __inline double _ode_fmax(double x, double y) { return __max(x, y); } |
||||
static __inline float _ode_fminf(float x, float y) { return __min(x, y); } |
||||
static __inline float _ode_fmaxf(float x, float y) { return __max(x, y); } |
||||
#else // #if !defined(_MSC_VER) || _MSC_VER >= 1700
|
||||
#define _ode_fmin(x, y) fmin(x, y) |
||||
#define _ode_fmax(x, y) fmax(x, y) |
||||
#define _ode_fminf(x, y) fminf(x, y) |
||||
#define _ode_fmaxf(x, y) fmaxf(x, y) |
||||
#endif // #if !defined(_MSC_VER) || _MSC_VER >= 1700
|
||||
|
||||
|
||||
#endif |
||||
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,467 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
/* C++ interface for new collision API */ |
||||
|
||||
|
||||
#ifndef _ODE_ODECPP_COLLISION_H_ |
||||
#define _ODE_ODECPP_COLLISION_H_ |
||||
#ifdef __cplusplus |
||||
|
||||
//#include <ode/error.h>
|
||||
|
||||
//namespace ode {
|
||||
|
||||
class dGeom { |
||||
// intentionally undefined, don't use these
|
||||
dGeom (dGeom &); |
||||
void operator= (dGeom &); |
||||
|
||||
protected: |
||||
dGeomID _id; |
||||
|
||||
dGeom() |
||||
{ _id = 0; } |
||||
public: |
||||
~dGeom() |
||||
{ if (_id) dGeomDestroy (_id); } |
||||
|
||||
dGeomID id() const |
||||
{ return _id; } |
||||
operator dGeomID() const |
||||
{ return _id; } |
||||
|
||||
void destroy() { |
||||
if (_id) dGeomDestroy (_id); |
||||
_id = 0; |
||||
} |
||||
|
||||
int getClass() const |
||||
{ return dGeomGetClass (_id); } |
||||
|
||||
dSpaceID getSpace() const |
||||
{ return dGeomGetSpace (_id); } |
||||
|
||||
void setData (void *data) |
||||
{ dGeomSetData (_id,data); } |
||||
void *getData() const |
||||
{ return dGeomGetData (_id); } |
||||
|
||||
void setBody (dBodyID b) |
||||
{ dGeomSetBody (_id,b); } |
||||
dBodyID getBody() const |
||||
{ return dGeomGetBody (_id); } |
||||
|
||||
void setPosition (dReal x, dReal y, dReal z) |
||||
{ dGeomSetPosition (_id,x,y,z); } |
||||
const dReal * getPosition() const |
||||
{ return dGeomGetPosition (_id); } |
||||
|
||||
void setRotation (const dMatrix3 R) |
||||
{ dGeomSetRotation (_id,R); } |
||||
const dReal * getRotation() const |
||||
{ return dGeomGetRotation (_id); } |
||||
|
||||
void setQuaternion (const dQuaternion quat) |
||||
{ dGeomSetQuaternion (_id,quat); } |
||||
void getQuaternion (dQuaternion quat) const |
||||
{ dGeomGetQuaternion (_id,quat); } |
||||
|
||||
void getAABB (dReal aabb[6]) const |
||||
{ dGeomGetAABB (_id, aabb); } |
||||
|
||||
int isSpace() |
||||
{ return dGeomIsSpace (_id); } |
||||
|
||||
void setCategoryBits (unsigned long bits) |
||||
{ dGeomSetCategoryBits (_id, bits); } |
||||
void setCollideBits (unsigned long bits) |
||||
{ dGeomSetCollideBits (_id, bits); } |
||||
unsigned long getCategoryBits() |
||||
{ return dGeomGetCategoryBits (_id); } |
||||
unsigned long getCollideBits() |
||||
{ return dGeomGetCollideBits (_id); } |
||||
|
||||
void enable() |
||||
{ dGeomEnable (_id); } |
||||
void disable() |
||||
{ dGeomDisable (_id); } |
||||
int isEnabled() |
||||
{ return dGeomIsEnabled (_id); } |
||||
|
||||
void getRelPointPos (dReal px, dReal py, dReal pz, dVector3 result) const |
||||
{ dGeomGetRelPointPos (_id, px, py, pz, result); } |
||||
void getRelPointPos (const dVector3 p, dVector3 result) const |
||||
{ getRelPointPos (p[0], p[1], p[2], result); } |
||||
|
||||
void getPosRelPoint (dReal px, dReal py, dReal pz, dVector3 result) const |
||||
{ dGeomGetPosRelPoint (_id, px, py, pz, result); } |
||||
void getPosRelPoint (const dVector3 p, dVector3 result) const |
||||
{ getPosRelPoint (p[0], p[1], p[2], result); } |
||||
|
||||
void vectorToWorld (dReal px, dReal py, dReal pz, dVector3 result) const |
||||
{ dGeomVectorToWorld (_id, px, py, pz, result); } |
||||
void vectorToWorld (const dVector3 p, dVector3 result) const |
||||
{ vectorToWorld (p[0], p[1], p[2], result); } |
||||
|
||||
void vectorFromWorld (dReal px, dReal py, dReal pz, dVector3 result) const |
||||
{ dGeomVectorFromWorld (_id, px, py, pz, result); } |
||||
void vectorFromWorld (const dVector3 p, dVector3 result) const |
||||
{ vectorFromWorld (p[0], p[1], p[2], result); } |
||||
|
||||
void collide2 (dGeomID g, void *data, dNearCallback *callback) |
||||
{ dSpaceCollide2 (_id,g,data,callback); } |
||||
}; |
||||
|
||||
|
||||
class dSpace : public dGeom { |
||||
// intentionally undefined, don't use these
|
||||
dSpace (dSpace &); |
||||
void operator= (dSpace &); |
||||
|
||||
protected: |
||||
// the default constructor is protected so that you
|
||||
// can't instance this class. you must instance one
|
||||
// of its subclasses instead.
|
||||
dSpace () { _id = 0; } |
||||
|
||||
public: |
||||
dSpaceID id() const |
||||
{ return (dSpaceID) _id; } |
||||
operator dSpaceID() const |
||||
{ return (dSpaceID) _id; } |
||||
|
||||
void setCleanup (int mode) |
||||
{ dSpaceSetCleanup (id(), mode); } |
||||
int getCleanup() |
||||
{ return dSpaceGetCleanup (id()); } |
||||
|
||||
void add (dGeomID x) |
||||
{ dSpaceAdd (id(), x); } |
||||
void remove (dGeomID x) |
||||
{ dSpaceRemove (id(), x); } |
||||
int query (dGeomID x) |
||||
{ return dSpaceQuery (id(),x); } |
||||
|
||||
int getNumGeoms() |
||||
{ return dSpaceGetNumGeoms (id()); } |
||||
dGeomID getGeom (int i) |
||||
{ return dSpaceGetGeom (id(),i); } |
||||
|
||||
void collide (void *data, dNearCallback *callback) |
||||
{ dSpaceCollide (id(),data,callback); } |
||||
}; |
||||
|
||||
|
||||
class dSimpleSpace : public dSpace { |
||||
// intentionally undefined, don't use these
|
||||
dSimpleSpace (dSimpleSpace &); |
||||
void operator= (dSimpleSpace &); |
||||
|
||||
public: |
||||
dSimpleSpace () |
||||
{ _id = (dGeomID) dSimpleSpaceCreate (0); } |
||||
dSimpleSpace (dSpace &space) |
||||
{ _id = (dGeomID) dSimpleSpaceCreate (space.id()); } |
||||
dSimpleSpace (dSpaceID space) |
||||
{ _id = (dGeomID) dSimpleSpaceCreate (space); } |
||||
}; |
||||
|
||||
|
||||
class dHashSpace : public dSpace { |
||||
// intentionally undefined, don't use these
|
||||
dHashSpace (dHashSpace &); |
||||
void operator= (dHashSpace &); |
||||
|
||||
public: |
||||
dHashSpace () |
||||
{ _id = (dGeomID) dHashSpaceCreate (0); } |
||||
dHashSpace (dSpace &space) |
||||
{ _id = (dGeomID) dHashSpaceCreate (space.id()); } |
||||
dHashSpace (dSpaceID space) |
||||
{ _id = (dGeomID) dHashSpaceCreate (space); } |
||||
|
||||
void setLevels (int minlevel, int maxlevel) |
||||
{ dHashSpaceSetLevels (id(),minlevel,maxlevel); } |
||||
}; |
||||
|
||||
|
||||
class dQuadTreeSpace : public dSpace { |
||||
// intentionally undefined, don't use these
|
||||
dQuadTreeSpace (dQuadTreeSpace &); |
||||
void operator= (dQuadTreeSpace &); |
||||
|
||||
public: |
||||
dQuadTreeSpace (const dVector3 center, const dVector3 extents, int depth) |
||||
{ _id = (dGeomID) dQuadTreeSpaceCreate (0,center,extents,depth); } |
||||
dQuadTreeSpace (dSpace &space, const dVector3 center, const dVector3 extents, int depth) |
||||
{ _id = (dGeomID) dQuadTreeSpaceCreate (space.id(),center,extents,depth); } |
||||
dQuadTreeSpace (dSpaceID space, const dVector3 center, const dVector3 extents, int depth) |
||||
{ _id = (dGeomID) dQuadTreeSpaceCreate (space,center,extents,depth); } |
||||
}; |
||||
|
||||
|
||||
class dSphere : public dGeom { |
||||
// intentionally undefined, don't use these
|
||||
dSphere (dSphere &); |
||||
void operator= (dSphere &); |
||||
|
||||
public: |
||||
dSphere () { } |
||||
dSphere (dReal radius) |
||||
{ _id = dCreateSphere (0, radius); } |
||||
dSphere (dSpace &space, dReal radius) |
||||
{ _id = dCreateSphere (space.id(), radius); } |
||||
dSphere (dSpaceID space, dReal radius) |
||||
{ _id = dCreateSphere (space, radius); } |
||||
|
||||
void create (dSpaceID space, dReal radius) { |
||||
if (_id) dGeomDestroy (_id); |
||||
_id = dCreateSphere (space, radius); |
||||
} |
||||
|
||||
void setRadius (dReal radius) |
||||
{ dGeomSphereSetRadius (_id, radius); } |
||||
dReal getRadius() const |
||||
{ return dGeomSphereGetRadius (_id); } |
||||
}; |
||||
|
||||
|
||||
class dBox : public dGeom { |
||||
// intentionally undefined, don't use these
|
||||
dBox (dBox &); |
||||
void operator= (dBox &); |
||||
|
||||
public: |
||||
dBox () { } |
||||
dBox (dReal lx, dReal ly, dReal lz) |
||||
{ _id = dCreateBox (0,lx,ly,lz); } |
||||
dBox (dSpace &space, dReal lx, dReal ly, dReal lz) |
||||
{ _id = dCreateBox (space,lx,ly,lz); } |
||||
dBox (dSpaceID space, dReal lx, dReal ly, dReal lz) |
||||
{ _id = dCreateBox (space,lx,ly,lz); } |
||||
|
||||
void create (dSpaceID space, dReal lx, dReal ly, dReal lz) { |
||||
if (_id) dGeomDestroy (_id); |
||||
_id = dCreateBox (space,lx,ly,lz); |
||||
} |
||||
|
||||
void setLengths (dReal lx, dReal ly, dReal lz) |
||||
{ dGeomBoxSetLengths (_id, lx, ly, lz); } |
||||
void getLengths (dVector3 result) const |
||||
{ dGeomBoxGetLengths (_id,result); } |
||||
}; |
||||
|
||||
|
||||
class dPlane : public dGeom { |
||||
// intentionally undefined, don't use these
|
||||
dPlane (dPlane &); |
||||
void operator= (dPlane &); |
||||
|
||||
public: |
||||
dPlane() { } |
||||
dPlane (dReal a, dReal b, dReal c, dReal d) |
||||
{ _id = dCreatePlane (0,a,b,c,d); } |
||||
dPlane (dSpace &space, dReal a, dReal b, dReal c, dReal d) |
||||
{ _id = dCreatePlane (space.id(),a,b,c,d); } |
||||
dPlane (dSpaceID space, dReal a, dReal b, dReal c, dReal d) |
||||
{ _id = dCreatePlane (space,a,b,c,d); } |
||||
|
||||
void create (dSpaceID space, dReal a, dReal b, dReal c, dReal d) { |
||||
if (_id) dGeomDestroy (_id); |
||||
_id = dCreatePlane (space,a,b,c,d); |
||||
} |
||||
|
||||
void setParams (dReal a, dReal b, dReal c, dReal d) |
||||
{ dGeomPlaneSetParams (_id, a, b, c, d); } |
||||
void getParams (dVector4 result) const |
||||
{ dGeomPlaneGetParams (_id,result); } |
||||
}; |
||||
|
||||
|
||||
class dCapsule : public dGeom { |
||||
// intentionally undefined, don't use these
|
||||
dCapsule (dCapsule &); |
||||
void operator= (dCapsule &); |
||||
|
||||
public: |
||||
dCapsule() { } |
||||
dCapsule (dReal radius, dReal length) |
||||
{ _id = dCreateCapsule (0,radius,length); } |
||||
dCapsule (dSpace &space, dReal radius, dReal length) |
||||
{ _id = dCreateCapsule (space.id(),radius,length); } |
||||
dCapsule (dSpaceID space, dReal radius, dReal length) |
||||
{ _id = dCreateCapsule (space,radius,length); } |
||||
|
||||
void create (dSpaceID space, dReal radius, dReal length) { |
||||
if (_id) dGeomDestroy (_id); |
||||
_id = dCreateCapsule (space,radius,length); |
||||
} |
||||
|
||||
void setParams (dReal radius, dReal length) |
||||
{ dGeomCapsuleSetParams (_id, radius, length); } |
||||
void getParams (dReal *radius, dReal *length) const |
||||
{ dGeomCapsuleGetParams (_id,radius,length); } |
||||
}; |
||||
|
||||
|
||||
class dCylinder : public dGeom { |
||||
// intentionally undefined, don't use these
|
||||
dCylinder (dCylinder &); |
||||
void operator= (dCylinder &); |
||||
|
||||
public: |
||||
dCylinder() { } |
||||
dCylinder (dReal radius, dReal length) |
||||
{ _id = dCreateCylinder (0,radius,length); } |
||||
dCylinder (dSpace &space, dReal radius, dReal length) |
||||
{ _id = dCreateCylinder (space.id(),radius,length); } |
||||
dCylinder (dSpaceID space, dReal radius, dReal length) |
||||
{ _id = dCreateCylinder (space,radius,length); } |
||||
|
||||
void create (dSpaceID space, dReal radius, dReal length) { |
||||
if (_id) dGeomDestroy (_id); |
||||
_id = dCreateCylinder (space,radius,length); |
||||
} |
||||
|
||||
void setParams (dReal radius, dReal length) |
||||
{ dGeomCylinderSetParams (_id, radius, length); } |
||||
void getParams (dReal *radius, dReal *length) const |
||||
{ dGeomCylinderGetParams (_id,radius,length); } |
||||
}; |
||||
|
||||
|
||||
class dRay : public dGeom { |
||||
// intentionally undefined, don't use these
|
||||
dRay (dRay &); |
||||
void operator= (dRay &); |
||||
|
||||
public: |
||||
dRay() { } |
||||
dRay (dReal length) |
||||
{ _id = dCreateRay (0,length); } |
||||
dRay (dSpace &space, dReal length) |
||||
{ _id = dCreateRay (space.id(),length); } |
||||
dRay (dSpaceID space, dReal length) |
||||
{ _id = dCreateRay (space,length); } |
||||
|
||||
void create (dSpaceID space, dReal length) { |
||||
if (_id) dGeomDestroy (_id); |
||||
_id = dCreateRay (space,length); |
||||
} |
||||
|
||||
void setLength (dReal length) |
||||
{ dGeomRaySetLength (_id, length); } |
||||
dReal getLength() |
||||
{ return dGeomRayGetLength (_id); } |
||||
|
||||
void set (dReal px, dReal py, dReal pz, dReal dx, dReal dy, dReal dz) |
||||
{ dGeomRaySet (_id, px, py, pz, dx, dy, dz); } |
||||
void get (dVector3 start, dVector3 dir) |
||||
{ dGeomRayGet (_id, start, dir); } |
||||
|
||||
#ifdef WIN32 |
||||
#pragma warning( push ) |
||||
#pragma warning( disable : 4996 ) |
||||
#else |
||||
#pragma GCC diagnostic push |
||||
#pragma GCC diagnostic ignored "-Wdeprecated-declarations" |
||||
#endif |
||||
ODE_API_DEPRECATED |
||||
void setParams (int firstContact, int backfaceCull) |
||||
{ dGeomRaySetParams (_id, firstContact, backfaceCull); } |
||||
|
||||
ODE_API_DEPRECATED |
||||
void getParams (int *firstContact, int *backfaceCull) |
||||
{ dGeomRayGetParams (_id, firstContact, backfaceCull); } |
||||
#ifdef WIN32 |
||||
#pragma warning( pop ) |
||||
#else |
||||
#pragma GCC diagnostic pop |
||||
#endif |
||||
void setBackfaceCull (int backfaceCull) |
||||
{ dGeomRaySetBackfaceCull (_id, backfaceCull); } |
||||
int getBackfaceCull() |
||||
{ return dGeomRayGetBackfaceCull (_id); } |
||||
|
||||
void setFirstContact (int firstContact) |
||||
{ dGeomRaySetFirstContact (_id, firstContact); } |
||||
int getFirstContact() |
||||
{ return dGeomRayGetFirstContact (_id); } |
||||
|
||||
void setClosestHit (int closestHit) |
||||
{ dGeomRaySetClosestHit (_id, closestHit); } |
||||
int getClosestHit() |
||||
{ return dGeomRayGetClosestHit (_id); } |
||||
}; |
||||
|
||||
#ifdef WIN32 |
||||
#pragma warning( push ) |
||||
#pragma warning( disable : 4996 ) |
||||
#else |
||||
#pragma GCC diagnostic push |
||||
#pragma GCC diagnostic ignored "-Wdeprecated-declarations" |
||||
#endif |
||||
|
||||
class ODE_API_DEPRECATED dGeomTransform : public dGeom { |
||||
// intentionally undefined, don't use these
|
||||
dGeomTransform (dGeomTransform &); |
||||
void operator= (dGeomTransform &); |
||||
|
||||
public: |
||||
dGeomTransform() { } |
||||
dGeomTransform (dSpace &space) |
||||
{ _id = dCreateGeomTransform (space.id()); } |
||||
dGeomTransform (dSpaceID space) |
||||
{ _id = dCreateGeomTransform (space); } |
||||
|
||||
void create (dSpaceID space=0) { |
||||
if (_id) dGeomDestroy (_id); |
||||
_id = dCreateGeomTransform (space); |
||||
} |
||||
|
||||
void setGeom (dGeomID geom) |
||||
{ dGeomTransformSetGeom (_id, geom); } |
||||
dGeomID getGeom() const |
||||
{ return dGeomTransformGetGeom (_id); } |
||||
|
||||
void setCleanup (int mode) |
||||
{ dGeomTransformSetCleanup (_id,mode); } |
||||
int getCleanup () |
||||
{ return dGeomTransformGetCleanup (_id); } |
||||
|
||||
void setInfo (int mode) |
||||
{ dGeomTransformSetInfo (_id,mode); } |
||||
int getInfo() |
||||
{ return dGeomTransformGetInfo (_id); } |
||||
}; |
||||
|
||||
#ifdef WIN32 |
||||
#pragma warning( pop ) |
||||
#else |
||||
#pragma GCC diagnostic pop |
||||
#endif |
||||
|
||||
//}
|
||||
|
||||
#endif |
||||
#endif |
||||
@ -0,0 +1,236 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
/* Library initialization/finalization functions. */ |
||||
|
||||
#ifndef _ODE_ODEINIT_H_ |
||||
#define _ODE_ODEINIT_H_ |
||||
|
||||
#include <ode/common.h> |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
/* ************************************************************************ */ |
||||
/* Library initialization */ |
||||
|
||||
/**
|
||||
* @defgroup init Library Initialization |
||||
* |
||||
* Library initialization functions prepare ODE internal data structures for use |
||||
* and release allocated resources after ODE is not needed any more. |
||||
*/ |
||||
|
||||
|
||||
/**
|
||||
* @brief Library initialization flags. |
||||
* |
||||
* These flags define ODE library initialization options. |
||||
* |
||||
* @c dInitFlagManualThreadCleanup indicates that resources allocated in TLS for threads |
||||
* using ODE are to be cleared by library client with explicit call to @c dCleanupODEAllDataForThread. |
||||
* If this flag is not specified the automatic resource tracking algorithm is used. |
||||
* |
||||
* With automatic resource tracking, On Windows, memory allocated for a thread may
|
||||
* remain not freed for some time after the thread exits. The resources may be
|
||||
* released when one of other threads calls @c dAllocateODEDataForThread. Ultimately, |
||||
* the resources are released when library is closed with @c dCloseODE. On other
|
||||
* operating systems resources are always released by the thread itself on its exit |
||||
* or on library closure with @c dCloseODE. |
||||
* |
||||
* With manual thread data cleanup mode every collision space object must be
|
||||
* explicitly switched to manual cleanup mode with @c dSpaceSetManualCleanup |
||||
* after creation. See description of the function for more details. |
||||
* |
||||
* If @c dInitFlagManualThreadCleanup was not specified during initialization, |
||||
* calls to @c dCleanupODEAllDataForThread are not allowed. |
||||
* |
||||
* @see dInitODE2 |
||||
* @see dAllocateODEDataForThread |
||||
* @see dSpaceSetManualCleanup |
||||
* @see dCloseODE |
||||
* @ingroup init |
||||
*/ |
||||
enum dInitODEFlags { |
||||
dInitFlagManualThreadCleanup = 0x00000001 /*@< Thread local data is to be cleared explicitly on @c dCleanupODEAllDataForThread function call*/ |
||||
}; |
||||
|
||||
/**
|
||||
* @brief Initializes ODE library. |
||||
* |
||||
* @c dInitODE is obsolete. @c dInitODE2 is to be used for library initialization. |
||||
* |
||||
* A call to @c dInitODE is equal to the following initialization sequence |
||||
* @code |
||||
* dInitODE2(0); |
||||
* dAllocateODEDataForThread(dAllocateMaskAll); |
||||
* @endcode |
||||
* |
||||
* @see dInitODE2 |
||||
* @see dAllocateODEDataForThread |
||||
* @ingroup init |
||||
*/ |
||||
ODE_API void dInitODE(void); |
||||
|
||||
/**
|
||||
* @brief Initializes ODE library. |
||||
* @param uiInitFlags Initialization options bitmask |
||||
* @return A nonzero if initialization succeeded and zero otherwise. |
||||
* |
||||
* This function must be called to initialize ODE library before first use. If
|
||||
* initialization succeeds the function may not be called again until library is
|
||||
* closed with a call to @c dCloseODE. |
||||
* |
||||
* The @a uiInitFlags parameter specifies initialization options to be used. These |
||||
* can be combination of zero or more @c dInitODEFlags flags. |
||||
* |
||||
* @note |
||||
* If @c dInitFlagManualThreadCleanup flag is used for initialization,
|
||||
* @c dSpaceSetManualCleanup must be called to set manual cleanup mode for every |
||||
* space object right after creation. Failure to do so may lead to resource leaks. |
||||
* |
||||
* @see dInitODEFlags |
||||
* @see dCloseODE |
||||
* @see dSpaceSetManualCleanup |
||||
* @ingroup init |
||||
*/ |
||||
ODE_API int dInitODE2(unsigned int uiInitFlags/*=0*/); |
||||
|
||||
|
||||
/**
|
||||
* @brief ODE data allocation flags. |
||||
* |
||||
* These flags are used to indicate which data is to be pre-allocated in call to |
||||
* @c dAllocateODEDataForThread. |
||||
* |
||||
* @c dAllocateFlagBasicData tells to allocate the basic data set required for |
||||
* normal library operation. This flag is equal to zero and is always implicitly
|
||||
* included. |
||||
* |
||||
* @c dAllocateFlagCollisionData tells that collision detection data is to be allocated. |
||||
* Collision detection functions may not be called if the data has not be allocated
|
||||
* in advance. If collision detection is not going to be used, it is not necessary |
||||
* to specify this flag. |
||||
* |
||||
* @c dAllocateMaskAll is a mask that can be used for for allocating all possible
|
||||
* data in cases when it is not known what exactly features of ODE will be used. |
||||
* The mask may not be used in combination with other flags. It is guaranteed to |
||||
* include all the current and future legal allocation flags. However, mature
|
||||
* applications should use explicit flags they need rather than allocating everything. |
||||
* |
||||
* @see dAllocateODEDataForThread |
||||
* @ingroup init |
||||
*/ |
||||
enum dAllocateODEDataFlags { |
||||
dAllocateFlagBasicData = 0, /*@< Allocate basic data required for library to operate*/ |
||||
|
||||
dAllocateFlagCollisionData = 0x00000001, /*@< Allocate data for collision detection*/ |
||||
|
||||
dAllocateMaskAll = ~0 /*@< Allocate all the possible data that is currently defined or will be defined in the future.*/ |
||||
}; |
||||
|
||||
/**
|
||||
* @brief Allocate thread local data to allow the thread calling ODE. |
||||
* @param uiAllocateFlags Allocation options bitmask. |
||||
* @return A nonzero if allocation succeeded and zero otherwise. |
||||
*
|
||||
* The function is required to be called for every thread that is going to use |
||||
* ODE. This function allocates the data that is required for accessing ODE from
|
||||
* current thread along with optional data required for particular ODE subsystems. |
||||
* |
||||
* @a uiAllocateFlags parameter can contain zero or more flags from @c dAllocateODEDataFlags |
||||
* enumerated type. Multiple calls with different allocation flags are allowed. |
||||
* The flags that are already allocated are ignored in subsequent calls. If zero |
||||
* is passed as the parameter, it means to only allocate the set of most important |
||||
* data the library can not operate without. |
||||
* |
||||
* If the function returns failure status it means that none of the requested
|
||||
* data has been allocated. The client may retry allocation attempt with the same
|
||||
* flags when more system resources are available. |
||||
* |
||||
* @see dAllocateODEDataFlags |
||||
* @see dCleanupODEAllDataForThread |
||||
* @ingroup init |
||||
*/ |
||||
ODE_API int dAllocateODEDataForThread(unsigned int uiAllocateFlags); |
||||
|
||||
/**
|
||||
* @brief Free thread local data that was allocated for current thread. |
||||
* |
||||
* If library was initialized with @c dInitFlagManualThreadCleanup flag the function
|
||||
* is required to be called on exit of every thread that was calling @c dAllocateODEDataForThread. |
||||
* Failure to call @c dCleanupODEAllDataForThread may result in some resources remaining
|
||||
* not freed until program exit. The function may also be called when ODE is still
|
||||
* being used to release resources allocated for all the current subsystems and
|
||||
* possibly proceed with data pre-allocation for other subsystems. |
||||
* |
||||
* The function can safely be called several times in a row. The function can be
|
||||
* called without prior invocation of @c dAllocateODEDataForThread. The function
|
||||
* may not be called before ODE is initialized with @c dInitODE2 or after library
|
||||
* has been closed with @c dCloseODE. A call to @c dCloseODE implicitly releases
|
||||
* all the thread local resources that might be allocated for all the threads that
|
||||
* were using ODE. |
||||
* |
||||
* If library was initialized without @c dInitFlagManualThreadCleanup flag
|
||||
* @c dCleanupODEAllDataForThread must not be called. |
||||
* |
||||
* @see dAllocateODEDataForThread |
||||
* @see dInitODE2 |
||||
* @see dCloseODE |
||||
* @ingroup init |
||||
*/ |
||||
ODE_API void dCleanupODEAllDataForThread(); |
||||
|
||||
|
||||
/**
|
||||
* @brief Close ODE after it is not needed any more. |
||||
* |
||||
* The function is required to be called when program does not need ODE features any more. |
||||
* The call to @c dCloseODE releases all the resources allocated for library |
||||
* including all the thread local data that might be allocated for all the threads |
||||
* that were using ODE. |
||||
* |
||||
* @c dCloseODE is a paired function for @c dInitODE2 and must only be called |
||||
* after successful library initialization. |
||||
* |
||||
* @note Important! |
||||
* Make sure that all the threads that were using ODE have already terminated
|
||||
* before calling @c dCloseODE. In particular it is not allowed to call |
||||
* @c dCleanupODEAllDataForThread after @c dCloseODE. |
||||
* |
||||
* @see dInitODE2 |
||||
* @see dCleanupODEAllDataForThread |
||||
* @ingroup init |
||||
*/ |
||||
ODE_API void dCloseODE(void); |
||||
|
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} /* extern "C" */ |
||||
#endif |
||||
|
||||
|
||||
#endif /* _ODE_ODEINIT_H_ */ |
||||
@ -0,0 +1,545 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_ODEMATH_H_ |
||||
#define _ODE_ODEMATH_H_ |
||||
|
||||
#include <ode/common.h> |
||||
|
||||
/*
|
||||
* macro to access elements i,j in an NxM matrix A, independent of the |
||||
* matrix storage convention. |
||||
*/ |
||||
#define dACCESS33(A,i,j) ((A)[(i)*4+(j)]) |
||||
|
||||
/*
|
||||
* Macro to test for valid floating point values |
||||
*/ |
||||
#define dVALIDVEC3(v) (!(dIsNan(v[0]) || dIsNan(v[1]) || dIsNan(v[2]))) |
||||
#define dVALIDVEC4(v) (!(dIsNan(v[0]) || dIsNan(v[1]) || dIsNan(v[2]) || dIsNan(v[3]))) |
||||
#define dVALIDMAT3(m) (!(dIsNan(m[0]) || dIsNan(m[1]) || dIsNan(m[2]) || dIsNan(m[3]) || dIsNan(m[4]) || dIsNan(m[5]) || dIsNan(m[6]) || dIsNan(m[7]) || dIsNan(m[8]) || dIsNan(m[9]) || dIsNan(m[10]) || dIsNan(m[11]))) |
||||
#define dVALIDMAT4(m) (!(dIsNan(m[0]) || dIsNan(m[1]) || dIsNan(m[2]) || dIsNan(m[3]) || dIsNan(m[4]) || dIsNan(m[5]) || dIsNan(m[6]) || dIsNan(m[7]) || dIsNan(m[8]) || dIsNan(m[9]) || dIsNan(m[10]) || dIsNan(m[11]) || dIsNan(m[12]) || dIsNan(m[13]) || dIsNan(m[14]) || dIsNan(m[15]) )) |
||||
|
||||
|
||||
ODE_PURE_INLINE void dZeroVector3(dVector3 res) |
||||
{ |
||||
res[dV3E_X] = REAL(0.0); |
||||
res[dV3E_Y] = REAL(0.0); |
||||
res[dV3E_Z] = REAL(0.0); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dAssignVector3(dVector3 res, dReal x, dReal y, dReal z) |
||||
{ |
||||
res[dV3E_X] = x; |
||||
res[dV3E_Y] = y; |
||||
res[dV3E_Z] = z; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dZeroMatrix3(dMatrix3 res) |
||||
{ |
||||
res[dM3E_XX] = REAL(0.0); res[dM3E_XY] = REAL(0.0); res[dM3E_XZ] = REAL(0.0); |
||||
res[dM3E_YX] = REAL(0.0); res[dM3E_YY] = REAL(0.0); res[dM3E_YZ] = REAL(0.0); |
||||
res[dM3E_ZX] = REAL(0.0); res[dM3E_ZY] = REAL(0.0); res[dM3E_ZZ] = REAL(0.0); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dZeroMatrix4(dMatrix4 res) |
||||
{ |
||||
res[dM4E_XX] = REAL(0.0); res[dM4E_XY] = REAL(0.0); res[dM4E_XZ] = REAL(0.0); res[dM4E_XO] = REAL(0.0); |
||||
res[dM4E_YX] = REAL(0.0); res[dM4E_YY] = REAL(0.0); res[dM4E_YZ] = REAL(0.0); res[dM4E_YO] = REAL(0.0); |
||||
res[dM4E_ZX] = REAL(0.0); res[dM4E_ZY] = REAL(0.0); res[dM4E_ZZ] = REAL(0.0); res[dM4E_ZO] = REAL(0.0); |
||||
res[dM4E_OX] = REAL(0.0); res[dM4E_OY] = REAL(0.0); res[dM4E_OZ] = REAL(0.0); res[dM4E_OO] = REAL(0.0); |
||||
} |
||||
|
||||
/* Some vector math */ |
||||
ODE_PURE_INLINE void dAddVectors3(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
const dReal res_0 = a[0] + b[0]; |
||||
const dReal res_1 = a[1] + b[1]; |
||||
const dReal res_2 = a[2] + b[2]; |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dSubtractVectors3(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
const dReal res_0 = a[0] - b[0]; |
||||
const dReal res_1 = a[1] - b[1]; |
||||
const dReal res_2 = a[2] - b[2]; |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dAddVectorScaledVector3(dReal *res, const dReal *a, const dReal *b, dReal b_scale) |
||||
{ |
||||
const dReal res_0 = a[0] + b_scale * b[0]; |
||||
const dReal res_1 = a[1] + b_scale * b[1]; |
||||
const dReal res_2 = a[2] + b_scale * b[2]; |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dAddScaledVectors3(dReal *res, const dReal *a, const dReal *b, dReal a_scale, dReal b_scale) |
||||
{ |
||||
const dReal res_0 = a_scale * a[0] + b_scale * b[0]; |
||||
const dReal res_1 = a_scale * a[1] + b_scale * b[1]; |
||||
const dReal res_2 = a_scale * a[2] + b_scale * b[2]; |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dAddThreeScaledVectors3(dReal *res, const dReal *a, const dReal *b, const dReal *c, dReal a_scale, dReal b_scale, dReal c_scale) |
||||
{ |
||||
const dReal res_0 = a_scale * a[0] + b_scale * b[0] + c_scale * c[0]; |
||||
const dReal res_1 = a_scale * a[1] + b_scale * b[1] + c_scale * c[1]; |
||||
const dReal res_2 = a_scale * a[2] + b_scale * b[2] + c_scale * c[2]; |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dScaleVector3(dReal *res, dReal nScale) |
||||
{ |
||||
res[0] *= nScale ; |
||||
res[1] *= nScale ; |
||||
res[2] *= nScale ; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dNegateVector3(dReal *res) |
||||
{ |
||||
res[0] = -res[0]; |
||||
res[1] = -res[1]; |
||||
res[2] = -res[2]; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dCopyVector3(dReal *res, const dReal *a) |
||||
{ |
||||
const dReal res_0 = a[0]; |
||||
const dReal res_1 = a[1]; |
||||
const dReal res_2 = a[2]; |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dCopyScaledVector3(dReal *res, const dReal *a, dReal nScale) |
||||
{ |
||||
const dReal res_0 = a[0] * nScale; |
||||
const dReal res_1 = a[1] * nScale; |
||||
const dReal res_2 = a[2] * nScale; |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dCopyNegatedVector3(dReal *res, const dReal *a) |
||||
{ |
||||
const dReal res_0 = -a[0]; |
||||
const dReal res_1 = -a[1]; |
||||
const dReal res_2 = -a[2]; |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dCopyVector4(dReal *res, const dReal *a) |
||||
{ |
||||
const dReal res_0 = a[0]; |
||||
const dReal res_1 = a[1]; |
||||
const dReal res_2 = a[2]; |
||||
const dReal res_3 = a[3]; |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; res[3] = res_3; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dCopyMatrix4x4(dReal *res, const dReal *a) |
||||
{ |
||||
dCopyVector4(res + 0, a + 0); |
||||
dCopyVector4(res + 4, a + 4); |
||||
dCopyVector4(res + 8, a + 8); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dCopyMatrix4x3(dReal *res, const dReal *a) |
||||
{ |
||||
dCopyVector3(res + 0, a + 0); |
||||
dCopyVector3(res + 4, a + 4); |
||||
dCopyVector3(res + 8, a + 8); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dGetMatrixColumn3(dReal *res, const dReal *a, unsigned n) |
||||
{ |
||||
const dReal res_0 = a[n + 0]; |
||||
const dReal res_1 = a[n + 4]; |
||||
const dReal res_2 = a[n + 8]; |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; |
||||
} |
||||
|
||||
ODE_PURE_INLINE dReal dCalcVectorLength3(const dReal *a) |
||||
{ |
||||
return dSqrt(a[0] * a[0] + a[1] * a[1] + a[2] * a[2]); |
||||
} |
||||
|
||||
ODE_PURE_INLINE dReal dCalcVectorLengthSquare3(const dReal *a) |
||||
{ |
||||
return (a[0] * a[0] + a[1] * a[1] + a[2] * a[2]); |
||||
} |
||||
|
||||
ODE_PURE_INLINE dReal dCalcPointDepth3(const dReal *test_p, const dReal *plane_p, const dReal *plane_n) |
||||
{ |
||||
return (plane_p[0] - test_p[0]) * plane_n[0] + (plane_p[1] - test_p[1]) * plane_n[1] + (plane_p[2] - test_p[2]) * plane_n[2]; |
||||
} |
||||
|
||||
|
||||
/*
|
||||
* 3-way dot product. _dCalcVectorDot3 means that elements of `a' and `b' are spaced |
||||
* step_a and step_b indexes apart respectively. dCalcVectorDot3() means dDot311. |
||||
*/ |
||||
|
||||
ODE_PURE_INLINE dReal _dCalcVectorDot3(const dReal *a, const dReal *b, unsigned step_a, unsigned step_b) |
||||
{ |
||||
return a[0] * b[0] + a[step_a] * b[step_b] + a[2 * step_a] * b[2 * step_b]; |
||||
} |
||||
|
||||
|
||||
ODE_PURE_INLINE dReal dCalcVectorDot3 (const dReal *a, const dReal *b) { return _dCalcVectorDot3(a,b,1,1); } |
||||
ODE_PURE_INLINE dReal dCalcVectorDot3_13 (const dReal *a, const dReal *b) { return _dCalcVectorDot3(a,b,1,3); } |
||||
ODE_PURE_INLINE dReal dCalcVectorDot3_31 (const dReal *a, const dReal *b) { return _dCalcVectorDot3(a,b,3,1); } |
||||
ODE_PURE_INLINE dReal dCalcVectorDot3_33 (const dReal *a, const dReal *b) { return _dCalcVectorDot3(a,b,3,3); } |
||||
ODE_PURE_INLINE dReal dCalcVectorDot3_14 (const dReal *a, const dReal *b) { return _dCalcVectorDot3(a,b,1,4); } |
||||
ODE_PURE_INLINE dReal dCalcVectorDot3_41 (const dReal *a, const dReal *b) { return _dCalcVectorDot3(a,b,4,1); } |
||||
ODE_PURE_INLINE dReal dCalcVectorDot3_44 (const dReal *a, const dReal *b) { return _dCalcVectorDot3(a,b,4,4); } |
||||
|
||||
|
||||
/*
|
||||
* cross product, set res = a x b. _dCalcVectorCross3 means that elements of `res', `a' |
||||
* and `b' are spaced step_res, step_a and step_b indexes apart respectively. |
||||
* dCalcVectorCross3() means dCross3111.
|
||||
*/ |
||||
|
||||
ODE_PURE_INLINE void _dCalcVectorCross3(dReal *res, const dReal *a, const dReal *b, unsigned step_res, unsigned step_a, unsigned step_b) |
||||
{ |
||||
const dReal res_0 = a[ step_a]*b[2*step_b] - a[2*step_a]*b[ step_b]; |
||||
const dReal res_1 = a[2*step_a]*b[ 0] - a[ 0]*b[2*step_b]; |
||||
const dReal res_2 = a[ 0]*b[ step_b] - a[ step_a]*b[ 0]; |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[ 0] = res_0; |
||||
res[ step_res] = res_1; |
||||
res[2*step_res] = res_2; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dCalcVectorCross3 (dReal *res, const dReal *a, const dReal *b) { _dCalcVectorCross3(res, a, b, 1, 1, 1); } |
||||
ODE_PURE_INLINE void dCalcVectorCross3_114(dReal *res, const dReal *a, const dReal *b) { _dCalcVectorCross3(res, a, b, 1, 1, 4); } |
||||
ODE_PURE_INLINE void dCalcVectorCross3_141(dReal *res, const dReal *a, const dReal *b) { _dCalcVectorCross3(res, a, b, 1, 4, 1); } |
||||
ODE_PURE_INLINE void dCalcVectorCross3_144(dReal *res, const dReal *a, const dReal *b) { _dCalcVectorCross3(res, a, b, 1, 4, 4); } |
||||
ODE_PURE_INLINE void dCalcVectorCross3_411(dReal *res, const dReal *a, const dReal *b) { _dCalcVectorCross3(res, a, b, 4, 1, 1); } |
||||
ODE_PURE_INLINE void dCalcVectorCross3_414(dReal *res, const dReal *a, const dReal *b) { _dCalcVectorCross3(res, a, b, 4, 1, 4); } |
||||
ODE_PURE_INLINE void dCalcVectorCross3_441(dReal *res, const dReal *a, const dReal *b) { _dCalcVectorCross3(res, a, b, 4, 4, 1); } |
||||
ODE_PURE_INLINE void dCalcVectorCross3_444(dReal *res, const dReal *a, const dReal *b) { _dCalcVectorCross3(res, a, b, 4, 4, 4); } |
||||
|
||||
ODE_PURE_INLINE void dAddVectorCross3(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
dReal tmp[3]; |
||||
dCalcVectorCross3(tmp, a, b); |
||||
dAddVectors3(res, res, tmp); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dSubtractVectorCross3(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
dReal tmp[3]; |
||||
dCalcVectorCross3(tmp, a, b); |
||||
dSubtractVectors3(res, res, tmp); |
||||
} |
||||
|
||||
|
||||
/*
|
||||
* set a 3x3 submatrix of A to a matrix such that submatrix(A)*b = a x b. |
||||
* A is stored by rows, and has `skip' elements per row. the matrix is |
||||
* assumed to be already zero, so this does not write zero elements! |
||||
* if (plus,minus) is (+,-) then a positive version will be written. |
||||
* if (plus,minus) is (-,+) then a negative version will be written. |
||||
*/ |
||||
|
||||
ODE_PURE_INLINE void dSetCrossMatrixPlus(dReal *res, const dReal *a, unsigned skip) |
||||
{ |
||||
const dReal a_0 = a[0], a_1 = a[1], a_2 = a[2]; |
||||
res[1] = -a_2; |
||||
res[2] = +a_1; |
||||
res[skip+0] = +a_2; |
||||
res[skip+2] = -a_0; |
||||
res[2*skip+0] = -a_1; |
||||
res[2*skip+1] = +a_0; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dSetCrossMatrixMinus(dReal *res, const dReal *a, unsigned skip) |
||||
{ |
||||
const dReal a_0 = a[0], a_1 = a[1], a_2 = a[2]; |
||||
res[1] = +a_2; |
||||
res[2] = -a_1; |
||||
res[skip+0] = -a_2; |
||||
res[skip+2] = +a_0; |
||||
res[2*skip+0] = +a_1; |
||||
res[2*skip+1] = -a_0; |
||||
} |
||||
|
||||
|
||||
/*
|
||||
* compute the distance between two 3D-vectors |
||||
*/ |
||||
|
||||
ODE_PURE_INLINE dReal dCalcPointsDistance3(const dReal *a, const dReal *b) |
||||
{ |
||||
dReal res; |
||||
dReal tmp[3]; |
||||
dSubtractVectors3(tmp, a, b); |
||||
res = dCalcVectorLength3(tmp); |
||||
return res; |
||||
} |
||||
|
||||
/*
|
||||
* special case matrix multiplication, with operator selection |
||||
*/ |
||||
|
||||
ODE_PURE_INLINE void _dMultiplyHelper0_331(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
const dReal res_0 = dCalcVectorDot3(a, b); |
||||
const dReal res_1 = dCalcVectorDot3(a + 4, b); |
||||
const dReal res_2 = dCalcVectorDot3(a + 8, b); |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void _dMultiplyHelper1_331(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
const dReal res_0 = dCalcVectorDot3_41(a, b); |
||||
const dReal res_1 = dCalcVectorDot3_41(a + 1, b); |
||||
const dReal res_2 = dCalcVectorDot3_41(a + 2, b); |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; |
||||
} |
||||
|
||||
ODE_PURE_INLINE void _dMultiplyHelper0_133(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
_dMultiplyHelper1_331(res, b, a); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void _dMultiplyHelper1_133(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
const dReal res_0 = dCalcVectorDot3_44(a, b); |
||||
const dReal res_1 = dCalcVectorDot3_44(a + 1, b); |
||||
const dReal res_2 = dCalcVectorDot3_44(a + 2, b); |
||||
/* Only assign after all the calculations are over to avoid incurring memory aliasing*/ |
||||
res[0] = res_0; res[1] = res_1; res[2] = res_2; |
||||
} |
||||
|
||||
/*
|
||||
Note: NEVER call any of these functions/macros with the same variable for A and C,
|
||||
it is not equivalent to A*=B. |
||||
*/ |
||||
|
||||
ODE_PURE_INLINE void dMultiply0_331(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
_dMultiplyHelper0_331(res, a, b); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dMultiply1_331(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
_dMultiplyHelper1_331(res, a, b); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dMultiply0_133(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
_dMultiplyHelper0_133(res, a, b); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dMultiply0_333(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
_dMultiplyHelper0_133(res + 0, a + 0, b); |
||||
_dMultiplyHelper0_133(res + 4, a + 4, b); |
||||
_dMultiplyHelper0_133(res + 8, a + 8, b); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dMultiply1_333(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
_dMultiplyHelper1_133(res + 0, b, a + 0); |
||||
_dMultiplyHelper1_133(res + 4, b, a + 1); |
||||
_dMultiplyHelper1_133(res + 8, b, a + 2); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dMultiply2_333(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
_dMultiplyHelper0_331(res + 0, b, a + 0); |
||||
_dMultiplyHelper0_331(res + 4, b, a + 4); |
||||
_dMultiplyHelper0_331(res + 8, b, a + 8); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dMultiplyAdd0_331(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
dReal tmp[3]; |
||||
_dMultiplyHelper0_331(tmp, a, b); |
||||
dAddVectors3(res, res, tmp); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dMultiplyAdd1_331(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
dReal tmp[3]; |
||||
_dMultiplyHelper1_331(tmp, a, b); |
||||
dAddVectors3(res, res, tmp); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dMultiplyAdd0_133(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
dReal tmp[3]; |
||||
_dMultiplyHelper0_133(tmp, a, b); |
||||
dAddVectors3(res, res, tmp); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dMultiplyAdd0_333(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
dReal tmp[3]; |
||||
_dMultiplyHelper0_133(tmp, a + 0, b); |
||||
dAddVectors3(res+ 0, res + 0, tmp); |
||||
_dMultiplyHelper0_133(tmp, a + 4, b); |
||||
dAddVectors3(res + 4, res + 4, tmp); |
||||
_dMultiplyHelper0_133(tmp, a + 8, b); |
||||
dAddVectors3(res + 8, res + 8, tmp); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dMultiplyAdd1_333(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
dReal tmp[3]; |
||||
_dMultiplyHelper1_133(tmp, b, a + 0); |
||||
dAddVectors3(res + 0, res + 0, tmp); |
||||
_dMultiplyHelper1_133(tmp, b, a + 1); |
||||
dAddVectors3(res + 4, res + 4, tmp); |
||||
_dMultiplyHelper1_133(tmp, b, a + 2); |
||||
dAddVectors3(res + 8, res + 8, tmp); |
||||
} |
||||
|
||||
ODE_PURE_INLINE void dMultiplyAdd2_333(dReal *res, const dReal *a, const dReal *b) |
||||
{ |
||||
dReal tmp[3]; |
||||
_dMultiplyHelper0_331(tmp, b, a + 0); |
||||
dAddVectors3(res + 0, res + 0, tmp); |
||||
_dMultiplyHelper0_331(tmp, b, a + 4); |
||||
dAddVectors3(res + 4, res + 4, tmp); |
||||
_dMultiplyHelper0_331(tmp, b, a + 8); |
||||
dAddVectors3(res + 8, res + 8, tmp); |
||||
} |
||||
|
||||
ODE_PURE_INLINE dReal dCalcMatrix3Det( const dReal* mat ) |
||||
{ |
||||
dReal det; |
||||
|
||||
det = mat[0] * ( mat[5]*mat[10] - mat[9]*mat[6] ) |
||||
- mat[1] * ( mat[4]*mat[10] - mat[8]*mat[6] ) |
||||
+ mat[2] * ( mat[4]*mat[9] - mat[8]*mat[5] ); |
||||
|
||||
return( det ); |
||||
} |
||||
|
||||
/**
|
||||
Closed form matrix inversion, copied from
|
||||
collision_util.h for use in the stepper. |
||||
|
||||
Returns the determinant.
|
||||
returns 0 and does nothing |
||||
if the matrix is singular. |
||||
*/ |
||||
ODE_PURE_INLINE dReal dInvertMatrix3(dReal *dst, const dReal *ma) |
||||
{ |
||||
dReal det;
|
||||
dReal detRecip; |
||||
|
||||
det = dCalcMatrix3Det( ma ); |
||||
|
||||
|
||||
/* Setting an arbitrary non-zero threshold
|
||||
for the determinant doesn't do anyone
|
||||
any favors. The condition number is the |
||||
important thing. If all the eigen-values
|
||||
of the matrix are small, so is the
|
||||
determinant, but it can still be well |
||||
conditioned.
|
||||
A single extremely large eigen-value could |
||||
push the determinant over threshold, but
|
||||
produce a very unstable result if the other |
||||
eigen-values are small. So we just say that |
||||
the determinant must be non-zero and trust the |
||||
caller to provide well-conditioned matrices. |
||||
*/ |
||||
if ( det == 0 ) |
||||
{ |
||||
return 0; |
||||
} |
||||
|
||||
detRecip = dRecip(det);
|
||||
|
||||
dst[0] = ( ma[5]*ma[10] - ma[6]*ma[9] ) * detRecip; |
||||
dst[1] = ( ma[9]*ma[2] - ma[1]*ma[10] ) * detRecip; |
||||
dst[2] = ( ma[1]*ma[6] - ma[5]*ma[2] ) * detRecip; |
||||
|
||||
dst[4] = ( ma[6]*ma[8] - ma[4]*ma[10] ) * detRecip; |
||||
dst[5] = ( ma[0]*ma[10] - ma[8]*ma[2] ) * detRecip; |
||||
dst[6] = ( ma[4]*ma[2] - ma[0]*ma[6] ) * detRecip; |
||||
|
||||
dst[8] = ( ma[4]*ma[9] - ma[8]*ma[5] ) * detRecip; |
||||
dst[9] = ( ma[8]*ma[1] - ma[0]*ma[9] ) * detRecip; |
||||
dst[10] = ( ma[0]*ma[5] - ma[1]*ma[4] ) * detRecip; |
||||
|
||||
return det; |
||||
} |
||||
|
||||
|
||||
/* Include legacy macros here */ |
||||
#include <ode/odemath_legacy.h> |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/*
|
||||
* normalize 3x1 and 4x1 vectors (i.e. scale them to unit length) |
||||
*/ |
||||
|
||||
/* For DLL export*/ |
||||
ODE_API int dSafeNormalize3 (dVector3 a); |
||||
ODE_API int dSafeNormalize4 (dVector4 a); |
||||
ODE_API void dNormalize3 (dVector3 a); /* Potentially asserts on zero vec*/ |
||||
ODE_API void dNormalize4 (dVector4 a); /* Potentially asserts on zero vec*/ |
||||
|
||||
/*
|
||||
* given a unit length "normal" vector n, generate vectors p and q vectors |
||||
* that are an orthonormal basis for the plane space perpendicular to n. |
||||
* i.e. this makes p,q such that n,p,q are all perpendicular to each other. |
||||
* q will equal n x p. if n is not unit length then p will be unit length but |
||||
* q wont be. |
||||
*/ |
||||
|
||||
ODE_API void dPlaneSpace (const dVector3 n, dVector3 p, dVector3 q); |
||||
/* Makes sure the matrix is a proper rotation, returns a boolean status */ |
||||
ODE_API int dOrthogonalizeR(dMatrix3 m); |
||||
|
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
|
||||
#endif |
||||
@ -0,0 +1,162 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_ODEMATH_LEGACY_H_ |
||||
#define _ODE_ODEMATH_LEGACY_H_ |
||||
|
||||
|
||||
/*
|
||||
* These macros are not used any more inside of ODE |
||||
* They are kept for backward compatibility with external code that |
||||
* might still be using them. |
||||
*/ |
||||
|
||||
/*
|
||||
* General purpose vector operations with other vectors or constants. |
||||
*/ |
||||
|
||||
#define dOP(a,op,b,c) do { \ |
||||
(a)[0] = ((b)[0]) op ((c)[0]); \
|
||||
(a)[1] = ((b)[1]) op ((c)[1]); \
|
||||
(a)[2] = ((b)[2]) op ((c)[2]); \
|
||||
} while (0) |
||||
#define dOPC(a,op,b,c) do { \ |
||||
(a)[0] = ((b)[0]) op (c); \
|
||||
(a)[1] = ((b)[1]) op (c); \
|
||||
(a)[2] = ((b)[2]) op (c); \
|
||||
} while (0) |
||||
#define dOPE(a,op,b) do {\ |
||||
(a)[0] op ((b)[0]); \
|
||||
(a)[1] op ((b)[1]); \
|
||||
(a)[2] op ((b)[2]); \
|
||||
} while (0) |
||||
#define dOPEC(a,op,c) do { \ |
||||
(a)[0] op (c); \
|
||||
(a)[1] op (c); \
|
||||
(a)[2] op (c); \
|
||||
} while (0) |
||||
|
||||
/* Define an equation with operators
|
||||
* For example this function can be used to replace |
||||
* <PRE> |
||||
* for (int i=0; i<3; ++i) |
||||
* a[i] += b[i] + c[i]; |
||||
* </PRE> |
||||
*/ |
||||
#define dOPE2(a,op1,b,op2,c) do { \ |
||||
(a)[0] op1 ((b)[0]) op2 ((c)[0]); \
|
||||
(a)[1] op1 ((b)[1]) op2 ((c)[1]); \
|
||||
(a)[2] op1 ((b)[2]) op2 ((c)[2]); \
|
||||
} while (0) |
||||
|
||||
|
||||
#define dLENGTHSQUARED(a) dCalcVectorLengthSquare3(a) |
||||
#define dLENGTH(a) dCalcVectorLength3(a) |
||||
#define dDISTANCE(a, b) dCalcPointsDistance3(a, b) |
||||
|
||||
|
||||
#define dDOT(a, b) dCalcVectorDot3(a, b) |
||||
#define dDOT13(a, b) dCalcVectorDot3_13(a, b) |
||||
#define dDOT31(a, b) dCalcVectorDot3_31(a, b) |
||||
#define dDOT33(a, b) dCalcVectorDot3_33(a, b) |
||||
#define dDOT14(a, b) dCalcVectorDot3_14(a, b) |
||||
#define dDOT41(a, b) dCalcVectorDot3_41(a, b) |
||||
#define dDOT44(a, b) dCalcVectorDot3_44(a, b) |
||||
|
||||
|
||||
/*
|
||||
* cross product, set a = b x c. dCROSSpqr means that elements of `a', `b' |
||||
* and `c' are spaced p, q and r indexes apart respectively. |
||||
* dCROSS() means dCROSS111. `op' is normally `=', but you can set it to |
||||
* +=, -= etc to get other effects. |
||||
*/ |
||||
|
||||
#define dCROSS(a,op,b,c) \ |
||||
do { \
|
||||
(a)[0] op ((b)[1]*(c)[2] - (b)[2]*(c)[1]); \
|
||||
(a)[1] op ((b)[2]*(c)[0] - (b)[0]*(c)[2]); \
|
||||
(a)[2] op ((b)[0]*(c)[1] - (b)[1]*(c)[0]); \
|
||||
} while(0) |
||||
#define dCROSSpqr(a,op,b,c,p,q,r) \ |
||||
do { \
|
||||
(a)[ 0] op ((b)[ q]*(c)[2*r] - (b)[2*q]*(c)[ r]); \
|
||||
(a)[ p] op ((b)[2*q]*(c)[ 0] - (b)[ 0]*(c)[2*r]); \
|
||||
(a)[2*p] op ((b)[ 0]*(c)[ r] - (b)[ q]*(c)[ 0]); \
|
||||
} while(0) |
||||
#define dCROSS114(a,op,b,c) dCROSSpqr(a,op,b,c,1,1,4) |
||||
#define dCROSS141(a,op,b,c) dCROSSpqr(a,op,b,c,1,4,1) |
||||
#define dCROSS144(a,op,b,c) dCROSSpqr(a,op,b,c,1,4,4) |
||||
#define dCROSS411(a,op,b,c) dCROSSpqr(a,op,b,c,4,1,1) |
||||
#define dCROSS414(a,op,b,c) dCROSSpqr(a,op,b,c,4,1,4) |
||||
#define dCROSS441(a,op,b,c) dCROSSpqr(a,op,b,c,4,4,1) |
||||
#define dCROSS444(a,op,b,c) dCROSSpqr(a,op,b,c,4,4,4) |
||||
|
||||
|
||||
/*
|
||||
* set a 3x3 submatrix of A to a matrix such that submatrix(A)*b = a x b. |
||||
* A is stored by rows, and has `skip' elements per row. the matrix is |
||||
* assumed to be already zero, so this does not write zero elements! |
||||
* if (plus,minus) is (+,-) then a positive version will be written. |
||||
* if (plus,minus) is (-,+) then a negative version will be written. |
||||
*/ |
||||
|
||||
#define dCROSSMAT(A,a,skip,plus,minus) \ |
||||
do { \
|
||||
(A)[1] = minus (a)[2]; \
|
||||
(A)[2] = plus (a)[1]; \
|
||||
(A)[(skip)+0] = plus (a)[2]; \
|
||||
(A)[(skip)+2] = minus (a)[0]; \
|
||||
(A)[2*(skip)+0] = minus (a)[1]; \
|
||||
(A)[2*(skip)+1] = plus (a)[0]; \
|
||||
} while(0) |
||||
|
||||
|
||||
|
||||
|
||||
/*
|
||||
Note: NEVER call any of these functions/macros with the same variable for A and C,
|
||||
it is not equivalent to A*=B. |
||||
*/ |
||||
|
||||
#define dMULTIPLY0_331(A, B, C) dMultiply0_331(A, B, C) |
||||
#define dMULTIPLY1_331(A, B, C) dMultiply1_331(A, B, C) |
||||
#define dMULTIPLY0_133(A, B, C) dMultiply0_133(A, B, C) |
||||
#define dMULTIPLY0_333(A, B, C) dMultiply0_333(A, B, C) |
||||
#define dMULTIPLY1_333(A, B, C) dMultiply1_333(A, B, C) |
||||
#define dMULTIPLY2_333(A, B, C) dMultiply2_333(A, B, C) |
||||
|
||||
#define dMULTIPLYADD0_331(A, B, C) dMultiplyAdd0_331(A, B, C) |
||||
#define dMULTIPLYADD1_331(A, B, C) dMultiplyAdd1_331(A, B, C) |
||||
#define dMULTIPLYADD0_133(A, B, C) dMultiplyAdd0_133(A, B, C) |
||||
#define dMULTIPLYADD0_333(A, B, C) dMultiplyAdd0_333(A, B, C) |
||||
#define dMULTIPLYADD1_333(A, B, C) dMultiplyAdd1_333(A, B, C) |
||||
#define dMULTIPLYADD2_333(A, B, C) dMultiplyAdd2_333(A, B, C) |
||||
|
||||
|
||||
/*
|
||||
* These macros are not used any more inside of ODE |
||||
* They are kept for backward compatibility with external code that |
||||
* might still be using them. |
||||
*/ |
||||
|
||||
|
||||
#endif /* #ifndef _ODE_ODEMATH_LEGACY_H_ */ |
||||
@ -0,0 +1,16 @@ |
||||
#ifndef _ODE_PRECISION_H_ |
||||
#define _ODE_PRECISION_H_ |
||||
|
||||
/* Define dSINGLE for single precision, dDOUBLE for double precision,
|
||||
* but never both! |
||||
*/ |
||||
|
||||
#if defined(dIDESINGLE) |
||||
#define dSINGLE |
||||
#elif defined(dIDEDOUBLE) |
||||
#define dDOUBLE |
||||
#else |
||||
#define dDOUBLE |
||||
#endif |
||||
|
||||
#endif |
||||
@ -0,0 +1,16 @@ |
||||
#ifndef _ODE_PRECISION_H_ |
||||
#define _ODE_PRECISION_H_ |
||||
|
||||
/* Define dSINGLE for single precision, dDOUBLE for double precision,
|
||||
* but never both! |
||||
*/ |
||||
|
||||
#if defined(dIDESINGLE) |
||||
#define dSINGLE |
||||
#elif defined(dIDEDOUBLE) |
||||
#define dDOUBLE |
||||
#else |
||||
#define @ODE_PRECISION@ |
||||
#endif |
||||
|
||||
#endif |
||||
@ -0,0 +1,70 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_ROTATION_H_ |
||||
#define _ODE_ROTATION_H_ |
||||
|
||||
#include <ode/common.h> |
||||
#include <ode/compatibility.h> |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
ODE_API void dRSetIdentity (dMatrix3 R); |
||||
|
||||
ODE_API void dRFromAxisAndAngle (dMatrix3 R, dReal ax, dReal ay, dReal az, |
||||
dReal angle); |
||||
|
||||
ODE_API void dRFromEulerAngles (dMatrix3 R, dReal phi, dReal theta, dReal psi); |
||||
|
||||
ODE_API void dRFrom2Axes (dMatrix3 R, dReal ax, dReal ay, dReal az, |
||||
dReal bx, dReal by, dReal bz); |
||||
|
||||
ODE_API void dRFromZAxis (dMatrix3 R, dReal ax, dReal ay, dReal az); |
||||
|
||||
ODE_API void dQSetIdentity (dQuaternion q); |
||||
|
||||
ODE_API void dQFromAxisAndAngle (dQuaternion q, dReal ax, dReal ay, dReal az, |
||||
dReal angle); |
||||
|
||||
/* Quaternion multiplication, analogous to the matrix multiplication routines. */ |
||||
/* qa = rotate by qc, then qb */ |
||||
ODE_API void dQMultiply0 (dQuaternion qa, const dQuaternion qb, const dQuaternion qc); |
||||
/* qa = rotate by qc, then by inverse of qb */ |
||||
ODE_API void dQMultiply1 (dQuaternion qa, const dQuaternion qb, const dQuaternion qc); |
||||
/* qa = rotate by inverse of qc, then by qb */ |
||||
ODE_API void dQMultiply2 (dQuaternion qa, const dQuaternion qb, const dQuaternion qc); |
||||
/* qa = rotate by inverse of qc, then by inverse of qb */ |
||||
ODE_API void dQMultiply3 (dQuaternion qa, const dQuaternion qb, const dQuaternion qc); |
||||
|
||||
ODE_API void dRfromQ (dMatrix3 R, const dQuaternion q); |
||||
ODE_API void dQfromR (dQuaternion q, const dMatrix3 R); |
||||
ODE_API void dDQfromW (dReal dq[4], const dVector3 w, const dQuaternion q); |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif |
||||
@ -0,0 +1,412 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* Threading support header file. * |
||||
* Copyright (C) 2011-2019 Oleh Derevenko. All rights reserved. * |
||||
* e-mail: odar@eleks.com (change all "a" to "e") * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
/*
|
||||
* ODE threading support interfaces
|
||||
*/ |
||||
|
||||
|
||||
#ifndef _ODE_THREADING_H_ |
||||
#define _ODE_THREADING_H_ |
||||
|
||||
#include <ode/odeconfig.h> |
||||
// Include <time.h> since time_t is used and it is not available by default in some OSes
|
||||
#include <time.h> |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
struct dxThreadingImplementation; |
||||
typedef struct dxThreadingImplementation *dThreadingImplementationID; |
||||
|
||||
typedef unsigned dmutexindex_t; |
||||
struct dxMutexGroup; |
||||
typedef struct dxMutexGroup *dMutexGroupID; |
||||
|
||||
|
||||
#define dTHREADING_THREAD_COUNT_UNLIMITED 0U |
||||
|
||||
|
||||
|
||||
/**
|
||||
* @brief Allocates a group of muteces. |
||||
* |
||||
* The Mutex allocated do not need to support recursive locking. |
||||
* |
||||
* The Mutex names are provided to aid in debugging and thread state tracking. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @param Mutex_count Number of Mutex to create |
||||
* @Mutex_names_ptr Pointer to optional Mutex names array to be associated with individual Mutex |
||||
* @returns MutexGroup ID or NULL if error occurred. |
||||
* |
||||
* @ingroup threading |
||||
* @see dMutexGroupFreeFunction |
||||
* @see dMutexGroupMutexLockFunction |
||||
* @see dMutexGroupMutexUnlockFunction |
||||
*/ |
||||
typedef dMutexGroupID dMutexGroupAllocFunction (dThreadingImplementationID impl, dmutexindex_t Mutex_count, const char *const *Mutex_names_ptr/*=NULL*/); |
||||
|
||||
/**
|
||||
* @brief Deletes a group of muteces. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @param mutex_group Mutex group to deallocate |
||||
* |
||||
* @ingroup threading |
||||
* @see dMutexGroupAllocFunction |
||||
* @see dMutexGroupMutexLockFunction |
||||
* @see dMutexGroupMutexUnlockFunction |
||||
*/ |
||||
typedef void dMutexGroupFreeFunction (dThreadingImplementationID impl, dMutexGroupID mutex_group); |
||||
|
||||
/**
|
||||
* @brief Locks a mutex in a group of muteces. |
||||
* |
||||
* The function is to block execution until requested mutex can be locked. |
||||
* |
||||
* Note: Mutex provided may not support recursive locking. Calling this function |
||||
* while mutex is already locked by current thread will result in unpredictable behavior. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @param mutex_group Mutex group to use for locking |
||||
* @param mutex_index The index of mutex to be locked (0..Mutex_count - 1) |
||||
* |
||||
* @ingroup threading |
||||
* @see dMutexGroupAllocFunction |
||||
* @see dMutexGroupFreeFunction |
||||
* @see dMutexGroupMutexUnlockFunction |
||||
*/ |
||||
typedef void dMutexGroupMutexLockFunction (dThreadingImplementationID impl, dMutexGroupID mutex_group, dmutexindex_t mutex_index); |
||||
|
||||
/**
|
||||
* @brief Attempts to lock a mutex in a group of muteces. |
||||
* |
||||
* The function is to lock the requested mutex if it is unoccupied or
|
||||
* immediately return failure if mutex is already locked by other thread. |
||||
* |
||||
* Note: Mutex provided may not support recursive locking. Calling this function |
||||
* while mutex is already locked by current thread will result in unpredictable behavior. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @param mutex_group Mutex group to use for locking |
||||
* @param mutex_index The index of mutex to be locked (0..Mutex_count - 1) |
||||
* @returns 1 for success (mutex is locked) and 0 for failure (mutex is not locked) |
||||
* |
||||
* @ingroup threading |
||||
* @see dMutexGroupAllocFunction |
||||
* @see dMutexGroupFreeFunction |
||||
* @see dMutexGroupMutexLockFunction |
||||
* @see dMutexGroupMutexUnlockFunction |
||||
*/ |
||||
/* typedef int dMutexGroupMutexTryLockFunction (dThreadingImplementationID impl, dMutexGroupID mutex_group, dmutexindex_t mutex_index);*/ |
||||
|
||||
/**
|
||||
* @brief Unlocks a mutex in a group of muteces. |
||||
* |
||||
* The function is to unlock the given mutex provided it had been locked before. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @param mutex_group Mutex group to use for unlocking |
||||
* @param mutex_index The index of mutex to be unlocked (0..Mutex_count - 1) |
||||
* |
||||
* @ingroup threading |
||||
* @see dMutexGroupAllocFunction |
||||
* @see dMutexGroupFreeFunction |
||||
* @see dMutexGroupMutexLockFunction |
||||
*/ |
||||
typedef void dMutexGroupMutexUnlockFunction (dThreadingImplementationID impl, dMutexGroupID mutex_group, dmutexindex_t mutex_index); |
||||
|
||||
|
||||
struct dxCallReleasee; |
||||
typedef struct dxCallReleasee *dCallReleaseeID; |
||||
|
||||
struct dxCallWait; |
||||
typedef struct dxCallWait *dCallWaitID; |
||||
|
||||
typedef dsizeint ddependencycount_t; |
||||
typedef ddiffint ddependencychange_t; |
||||
typedef dsizeint dcallindex_t; |
||||
typedef int dThreadedCallFunction(void *call_context, dcallindex_t instance_index,
|
||||
dCallReleaseeID this_releasee); |
||||
|
||||
typedef struct dxThreadedWaitTime |
||||
{ |
||||
time_t wait_sec; |
||||
unsigned long wait_nsec; |
||||
|
||||
} dThreadedWaitTime; |
||||
|
||||
|
||||
/**
|
||||
* @brief Allocates a Wait ID that can be used to wait for a call. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @returns Wait ID or NULL if error occurred |
||||
* |
||||
* @ingroup threading |
||||
* @see dThreadedCallWaitResetFunction |
||||
* @see dThreadedCallWaitFreeFunction |
||||
* @see dThreadedCallPostFunction |
||||
* @see dThreadedCallWaitFunction |
||||
*/ |
||||
typedef dCallWaitID dThreadedCallWaitAllocFunction(dThreadingImplementationID impl); |
||||
|
||||
/**
|
||||
* @brief Resets a Wait ID so that it could be used to wait for another call. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @param call_wait Wait ID to reset |
||||
* |
||||
* @ingroup threading |
||||
* @see dThreadedCallWaitAllocFunction |
||||
* @see dThreadedCallWaitFreeFunction |
||||
* @see dThreadedCallPostFunction |
||||
* @see dThreadedCallWaitFunction |
||||
*/ |
||||
typedef void dThreadedCallWaitResetFunction(dThreadingImplementationID impl, dCallWaitID call_wait); |
||||
|
||||
/**
|
||||
* @brief Frees a Wait ID. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @param call_wait Wait ID to delete |
||||
* |
||||
* @ingroup threading |
||||
* @see dThreadedCallWaitAllocFunction |
||||
* @see dThreadedCallPostFunction |
||||
* @see dThreadedCallWaitFunction |
||||
*/ |
||||
typedef void dThreadedCallWaitFreeFunction(dThreadingImplementationID impl, dCallWaitID call_wait); |
||||
|
||||
|
||||
/**
|
||||
* @brief Post a function to be called in another thread. |
||||
* |
||||
* A call is scheduled to be executed asynchronously. |
||||
* |
||||
* A @a out_summary_fault variable can be provided for call to accumulate any |
||||
* possible faults from its execution and execution of any possible sub-calls. |
||||
* This variable gets result that @a call_func returns. Also, if dependent calls
|
||||
* are executed after the call already exits, the variable is also going to be
|
||||
* updated with results of all those calls before control is released to master. |
||||
* |
||||
* @a out_post_releasee parameter receives a value of @c dCallReleaseeID that can
|
||||
* later be used for @a dependent_releasee while scheduling sub-calls to make
|
||||
* current call depend on them. The value is only returned if @a dependencies_count
|
||||
* is not zero (i.e. if any dependencies are expected at all). The call is not going
|
||||
* to start until all its dependencies complete. |
||||
* |
||||
* In case if number of dependencies is unknown in advance 1 can be passed on call |
||||
* scheduling. Then @c dThreadedCallDependenciesCountAlterFunction can be used to |
||||
* add one more extra dependencies before scheduling each subcall. And then, after |
||||
* all sub-calls had been scheduled, @c dThreadedCallDependenciesCountAlterFunction |
||||
* can be used again to subtract initial extra dependency from total number. |
||||
* Adding one dependency in advance is necessary to obtain releasee ID and to make
|
||||
* sure the call will not start and will not terminate before all sub-calls are scheduled. |
||||
* |
||||
* Extra dependencies can also be added from the call itself after it has already
|
||||
* been started (with parameter received in @c dThreadedCallFunction).
|
||||
* In that case those dependencies will start immediately or after call returns
|
||||
* but the call's master will not be released/notified until all additional |
||||
* dependencies complete. This can be used to schedule sub-calls from a call and
|
||||
* then pass own job to another sub-call dependent on those initial sub-calls. |
||||
* |
||||
* By using @ call_wait it is possible to assign a Wait ID that can later
|
||||
* be passed into @c dThreadedCallWaitFunction to wait for call completion. |
||||
* |
||||
* If @a call_name is available (and it should!) the string must remain valid until |
||||
* after call completion. In most cases this should be a static string literal. |
||||
*
|
||||
* Since the function is an analogue of normal method call it is not supposed to fail. |
||||
* Any complications with resource allocation on call scheduling should be
|
||||
* anticipated, avoided and worked around by implementation. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @param out_summary_fault Optional pointer to variable to be set to 1 if function
|
||||
* call (or any sub-call) fails internally, or 0 if all calls return success |
||||
* @param out_post_releasee Optional pointer to variable to receive releasee ID
|
||||
* associated with the call |
||||
* @param dependencies_count Number of dependencies that are going to reference |
||||
* this call as dependent releasee |
||||
* @param dependent_releasee Optional releasee ID to reference with this call |
||||
* @param call_wait Optional Wait ID that can later be used to wait for the call |
||||
* @param call_func Pointer to function to be called |
||||
* @param call_context Context parameter to be passed into the call |
||||
* @param instance_index Index parameter to be passed into the call |
||||
* @param call_name Optional name to be associated with the call (for debugging and state tracking) |
||||
* |
||||
* @ingroup threading |
||||
* @see dThreadedCallWaitFunction |
||||
* @see dThreadedCallDependenciesCountAlterFunction |
||||
* @see dThreadingImplResourcesForCallsPreallocateFunction |
||||
*/ |
||||
typedef void dThreadedCallPostFunction(dThreadingImplementationID impl, int *out_summary_fault/*=NULL*/,
|
||||
dCallReleaseeID *out_post_releasee/*=NULL*/, ddependencycount_t dependencies_count, dCallReleaseeID dependent_releasee/*=NULL*/,
|
||||
dCallWaitID call_wait/*=NULL*/,
|
||||
dThreadedCallFunction *call_func, void *call_context, dcallindex_t instance_index,
|
||||
const char *call_name/*=NULL*/); |
||||
|
||||
/**
|
||||
* @brief Add or remove extra dependencies from call that has been scheduled |
||||
* or is in process of execution. |
||||
* |
||||
* Extra dependencies can be added to a call if exact number of sub-calls is |
||||
* not known in advance at the moment the call is scheduled. Also, some dependencies |
||||
* can be removed if sub-calls were planned but then dropped.
|
||||
* |
||||
* In case if total dependency count of a call reaches zero by result of invoking
|
||||
* this function, the call is free to start executing immediately. |
||||
* |
||||
* After the call execution had been started, any additional dependencies can only |
||||
* be added from the call function itself! |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @param target_releasee ID of releasee to apply dependencies count change to |
||||
* @param dependencies_count_change Number of dependencies to add or remove |
||||
* |
||||
* @ingroup threading |
||||
* @see dThreadedCallPostFunction |
||||
*/ |
||||
typedef void dThreadedCallDependenciesCountAlterFunction(dThreadingImplementationID impl, dCallReleaseeID target_releasee,
|
||||
ddependencychange_t dependencies_count_change); |
||||
|
||||
/**
|
||||
* @brief Wait for a posted call to complete. |
||||
* |
||||
* Function blocks until a call identified by @a call_wait completes or |
||||
* timeout elapses. |
||||
* |
||||
* IT IS ILLEGAL TO INVOKE THIS FUNCTION FROM WITHIN A THREADED CALL! |
||||
* This is because doing so will block a physical thread and will require
|
||||
* increasing worker thread count to avoid starvation. Use call dependencies
|
||||
* if it is necessary make sure sub-calls have been completed instead! |
||||
* |
||||
* If @a timeout_time_ptr is NULL, the function waits without time limit. If @a timeout_time_ptr |
||||
* points to zero value, the function only checks status and does not block. |
||||
* |
||||
* If @a wait_name is available (and it should!) the string must remain valid for |
||||
* the duration of wait. In most cases this should be a static string literal. |
||||
*
|
||||
* Function is not expected to return failures caused by system call faults as
|
||||
* those are hardly ever possible to be handled in this case anyway. In event of
|
||||
* system call fault the function is supposed to terminate application. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @param out_wait_status Optional pointer to variable to receive 1 if waiting succeeded |
||||
* or 0 in case of timeout |
||||
* @param call_wait Wait ID that had been passed to scheduling a call that needs to be waited for |
||||
* @param timeout_time_ptr Optional pointer to time specification the wait must not |
||||
* last longer than (pass NULL for infinite timeout) |
||||
* @param wait_name Optional name to be associated with the wait (for debugging and state tracking) |
||||
* |
||||
* @ingroup threading |
||||
* @see dThreadedCallPostFunction |
||||
*/ |
||||
typedef void dThreadedCallWaitFunction(dThreadingImplementationID impl, int *out_wait_status/*=NULL*/,
|
||||
dCallWaitID call_wait, const dThreadedWaitTime *timeout_time_ptr/*=NULL*/,
|
||||
const char *wait_name/*=NULL*/); |
||||
|
||||
/**
|
||||
* @brief Retrieve number of active threads that serve the implementation. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @returns Number of active threads |
||||
* |
||||
* @ingroup threading |
||||
*/ |
||||
typedef unsigned dThreadingImplThreadCountRetrieveFunction(dThreadingImplementationID impl); |
||||
|
||||
/**
|
||||
* @brief Preallocate resources to handle posted calls. |
||||
* |
||||
* The function is intended to make sure enough resources is preallocated for the |
||||
* implementation to be able to handle posted calls. Then @c max_simultaneous_calls_estimate |
||||
* is an estimate of how many posted calls can potentially be active or scheduled
|
||||
* at the same time. The value is usually derived from the way the calls are posted
|
||||
* in library code and dependencies between them. |
||||
*
|
||||
* @warning While working on an implementation be prepared that the estimate provided
|
||||
* yet rarely but theoretically can be exceeded due to unpredictability of thread execution. |
||||
* |
||||
* This function is normally going to be invoked by library each time it is entered |
||||
* from outside to do the job but before any threaded calls are going to be posted. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @param max_simultaneous_calls_estimate An estimated number of calls that can be posted simultaneously |
||||
* @returns 1 or 0 to indicate success or failure |
||||
* |
||||
* @ingroup threading |
||||
* @see dThreadedCallPostFunction |
||||
*/ |
||||
typedef int dThreadingImplResourcesForCallsPreallocateFunction(dThreadingImplementationID impl,
|
||||
ddependencycount_t max_simultaneous_calls_estimate); |
||||
|
||||
|
||||
/**
|
||||
* @brief An interface structure with function pointers to be provided by threading implementation. |
||||
*/ |
||||
typedef struct dxThreadingFunctionsInfo |
||||
{ |
||||
unsigned struct_size; |
||||
|
||||
dMutexGroupAllocFunction *alloc_mutex_group; |
||||
dMutexGroupFreeFunction *free_mutex_group; |
||||
dMutexGroupMutexLockFunction *lock_group_mutex; |
||||
dMutexGroupMutexUnlockFunction *unlock_group_mutex; |
||||
|
||||
dThreadedCallWaitAllocFunction *alloc_call_wait; |
||||
dThreadedCallWaitResetFunction *reset_call_wait; |
||||
dThreadedCallWaitFreeFunction *free_call_wait; |
||||
|
||||
dThreadedCallPostFunction *post_call; |
||||
dThreadedCallDependenciesCountAlterFunction *alter_call_dependencies_count; |
||||
dThreadedCallWaitFunction *wait_call; |
||||
|
||||
dThreadingImplThreadCountRetrieveFunction *retrieve_thread_count; |
||||
dThreadingImplResourcesForCallsPreallocateFunction *preallocate_resources_for_calls;
|
||||
|
||||
/*
|
||||
* Beware of Jon Watte's anger if you dare to uncomment this! |
||||
* May cryptic text below be you a warning! |
||||
* Стародавні легенди розказують, що кожного сміливця, хто наважиться порушити табу
|
||||
* і відкрити заборонений код, спіткає страшне прокляття і він відразу почне робити
|
||||
* одні лиш помилки. |
||||
* |
||||
* dMutexGroupMutexTryLockFunction *trylock_group_mutex; |
||||
*/ |
||||
|
||||
} dThreadingFunctionsInfo; |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif /* #ifndef _ODE_THREADING_H_ */ |
||||
@ -0,0 +1,292 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* Builtin ODE threading implementation header. * |
||||
* Copyright (C) 2011-2019 Oleh Derevenko. All rights reserved. * |
||||
* e-mail: odar@eleks.com (change all "a" to "e") * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
/*
|
||||
* A threading implementation built into ODE for those who does not care to
|
||||
* or can't implement an own one. |
||||
*/ |
||||
|
||||
#ifndef _ODE_THREADING_IMPL_H_ |
||||
#define _ODE_THREADING_IMPL_H_ |
||||
|
||||
|
||||
#include <ode/odeconfig.h> |
||||
#include <ode/threading.h> |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
struct dxThreadingThreadPool; |
||||
typedef struct dxThreadingThreadPool *dThreadingThreadPoolID; |
||||
|
||||
|
||||
/**
|
||||
* @brief Allocates built-in self-threaded threading implementation object. |
||||
* |
||||
* A self-threaded implementation is a type of implementation that performs
|
||||
* processing of posted calls by means of caller thread itself. This type of
|
||||
* implementation does not need thread pool to serve it. |
||||
*
|
||||
* Note that since May 9th, 2017 (rev. #2066) the Self-Threaded implementation
|
||||
* returns 0 rather than 1 as available thread count to distinguish from
|
||||
* thread pools with just one thread in them. |
||||
* |
||||
* The processing is arranged in a way to prevent call stack depth growth
|
||||
* as more and more nested calls are posted. |
||||
* |
||||
* Note that it is not necessary to create and assign a self-threaded
|
||||
* implementation to a world, as there is a global one used by default
|
||||
* if no implementation is explicitly assigned. You should only assign
|
||||
* each world an individual threading implementation instance if simulations
|
||||
* need to be run in parallel in multiple threads for the worlds. |
||||
* |
||||
* @returns ID of object allocated or NULL on failure |
||||
*
|
||||
* @ingroup threading |
||||
* @see dThreadingAllocateMultiThreadedImplementation |
||||
* @see dThreadingFreeImplementation |
||||
*/ |
||||
ODE_API dThreadingImplementationID dThreadingAllocateSelfThreadedImplementation(); |
||||
|
||||
/**
|
||||
* @brief Allocates built-in multi-threaded threading implementation object. |
||||
* |
||||
* A multi-threaded implementation is a type of implementation that has to be
|
||||
* served with a thread pool. The thread pool can be either the built-in ODE object |
||||
* or set of external threads that dedicate themselves to this purpose and stay |
||||
* in ODE until implementation releases them. |
||||
*
|
||||
* @returns ID of object allocated or NULL on failure |
||||
*
|
||||
* @ingroup threading |
||||
* @see dThreadingThreadPoolServeMultiThreadedImplementation |
||||
* @see dExternalThreadingServeMultiThreadedImplementation |
||||
* @see dThreadingFreeImplementation |
||||
*/ |
||||
ODE_API dThreadingImplementationID dThreadingAllocateMultiThreadedImplementation(); |
||||
|
||||
/**
|
||||
* @brief Retrieves the functions record of a built-in threading implementation. |
||||
* |
||||
* The implementation can be the one allocated by ODE (from @c dThreadingAllocateMultiThreadedImplementation).
|
||||
* Do not use this function with self-made custom implementations -
|
||||
* they should be bundled with their own set of functions. |
||||
*
|
||||
* @param impl Threading implementation ID |
||||
* @returns Pointer to associated functions structure |
||||
*
|
||||
* @ingroup threading |
||||
* @see dThreadingAllocateMultiThreadedImplementation |
||||
*/ |
||||
ODE_API const dThreadingFunctionsInfo *dThreadingImplementationGetFunctions(dThreadingImplementationID impl); |
||||
|
||||
/**
|
||||
* @brief Requests a built-in implementation to release threads serving it. |
||||
* |
||||
* The function unblocks threads employed in implementation serving and lets them
|
||||
* return to from where they originate. It's the responsibility of external code
|
||||
* to make sure all the calls to ODE that might be dependent on given threading
|
||||
* implementation object had already returned before this call is made. If threading
|
||||
* implementation is still processing some posted calls while this function is
|
||||
* invoked the behavior is implementation dependent. |
||||
* |
||||
* This call is to be used to request the threads to be released before waiting
|
||||
* for them in host pool or before waiting for them to exit. Implementation object
|
||||
* must not be destroyed before it is known that all the serving threads have already
|
||||
* returned from it. If implementation needs to be reused after this function is called |
||||
* and all the threads have exited from it a call to @c dThreadingImplementationCleanupForRestart |
||||
* must be made to restore internal state of the object. |
||||
* |
||||
* If this function is called for self-threaded built-in threading implementation |
||||
* the call has no effect. |
||||
*
|
||||
* @param impl Threading implementation ID |
||||
*
|
||||
* @ingroup threading |
||||
* @see dThreadingAllocateMultiThreadedImplementation |
||||
* @see dThreadingImplementationCleanupForRestart |
||||
*/ |
||||
ODE_API void dThreadingImplementationShutdownProcessing(dThreadingImplementationID impl); |
||||
|
||||
/**
|
||||
* @brief Restores built-in implementation's state to let it be reused after shutdown. |
||||
* |
||||
* If a multi-threaded built-in implementation needs to be reused after a call |
||||
* to @c dThreadingImplementationShutdownProcessing this call is to be made to
|
||||
* restore object's internal state. After that the implementation can be served again. |
||||
* |
||||
* If this function is called for self-threaded built-in threading implementation |
||||
* the call has no effect. |
||||
*
|
||||
* @param impl Threading implementation ID |
||||
*
|
||||
* @ingroup threading |
||||
* @see dThreadingAllocateMultiThreadedImplementation |
||||
* @see dThreadingImplementationShutdownProcessing |
||||
*/ |
||||
ODE_API void dThreadingImplementationCleanupForRestart(dThreadingImplementationID impl); |
||||
|
||||
/**
|
||||
* @brief Deletes an instance of built-in threading implementation. |
||||
* |
||||
* @warning A care must be taken to make sure the implementation is unassigned |
||||
* from all the objects it was assigned to and that there are no more threads
|
||||
* serving it before attempting to call this function. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
*
|
||||
* @ingroup threading |
||||
* @see dThreadingAllocateMultiThreadedImplementation |
||||
*/ |
||||
ODE_API void dThreadingFreeImplementation(dThreadingImplementationID impl); |
||||
|
||||
|
||||
typedef void (dThreadReadyToServeCallback)(void *callback_context); |
||||
|
||||
/**
|
||||
* @brief An entry point for external threads that would like to serve a built-in
|
||||
* threading implementation object. |
||||
* |
||||
* A thread that calls this function remains blocked in ODE and serves implementation |
||||
* object @p impl until being released with @c dThreadingImplementationShutdownProcessing call. |
||||
* This function can be used to provide external threads instead of ODE's built-in |
||||
* thread pools. |
||||
* |
||||
* The optional callback @readiness_callback is called after the thread has reached
|
||||
* and has registered within the implementation. The implementation should not
|
||||
* be used until all dedicated threads register within it as otherwise it will not |
||||
* have accurate view of the execution resources available. |
||||
* |
||||
* @param impl Threading implementation ID |
||||
* @param readiness_callback Optional readiness callback to be called after thread enters the implementation |
||||
* @param callback_context A value to be passed as parameter to readiness callback |
||||
*
|
||||
* @ingroup threading |
||||
* @see dThreadingAllocateMultiThreadedImplementation |
||||
* @see dThreadingImplementationShutdownProcessing |
||||
*/ |
||||
ODE_API void dExternalThreadingServeMultiThreadedImplementation(dThreadingImplementationID impl,
|
||||
dThreadReadyToServeCallback *readiness_callback/*=NULL*/, void *callback_context/*=NULL*/); |
||||
|
||||
|
||||
/**
|
||||
* @brief Creates an instance of built-in thread pool object that can be used to serve |
||||
* multi-threaded threading implementations. |
||||
* |
||||
* The threads allocated inherit priority of caller thread. Their affinity is not |
||||
* explicitly adjusted and gets the value the system assigns by default. Threads
|
||||
* have their stack memory fully committed immediately on start. On POSIX platforms
|
||||
* threads are started with all the possible signals blocked. Threads execute
|
||||
* calls to @c dAllocateODEDataForThread with @p ode_data_allocate_flags
|
||||
* on initialization. |
||||
* |
||||
* On POSIX platforms this function must be called with signals masked
|
||||
* or other measures must be taken to prevent reception of signals by calling thread
|
||||
* for the duration of the call. |
||||
*
|
||||
* @param thread_count Number of threads to start in pool |
||||
* @param stack_size Size of stack to be used for every thread or 0 for system default value |
||||
* @param ode_data_allocate_flags Flags to be passed to @c dAllocateODEDataForThread on behalf of each thread |
||||
* @returns ID of object allocated or NULL on failure |
||||
* |
||||
* @ingroup threading |
||||
* @see dThreadingAllocateMultiThreadedImplementation |
||||
* @see dThreadingImplementationShutdownProcessing |
||||
* @see dThreadingFreeThreadPool |
||||
*/ |
||||
ODE_API dThreadingThreadPoolID dThreadingAllocateThreadPool(unsigned thread_count,
|
||||
dsizeint stack_size, unsigned int ode_data_allocate_flags, void *reserved/*=NULL*/); |
||||
|
||||
/**
|
||||
* @brief Commands an instance of built-in thread pool to serve a built-in multi-threaded
|
||||
* threading implementation. |
||||
* |
||||
* A pool can only serve one threading implementation at a time.
|
||||
* Call @c dThreadingImplementationShutdownProcessing to release pool threads
|
||||
* from implementation serving and make them idle. Pool threads must be released
|
||||
* from any implementations before pool is attempted to be deleted. |
||||
* |
||||
* This function waits for threads to register within implementation before returning. |
||||
* So, after the function call exits the implementation can be used immediately. |
||||
*
|
||||
* @param pool Thread pool ID to serve the implementation |
||||
* @param impl Implementation ID of implementation to be served |
||||
* |
||||
* @ingroup threading |
||||
* @see dThreadingAllocateThreadPool |
||||
* @see dThreadingAllocateMultiThreadedImplementation |
||||
* @see dThreadingImplementationShutdownProcessing |
||||
*/ |
||||
ODE_API void dThreadingThreadPoolServeMultiThreadedImplementation(dThreadingThreadPoolID pool, dThreadingImplementationID impl); |
||||
|
||||
/**
|
||||
* @brief Waits until all pool threads are released from threading implementation
|
||||
* they might be serving. |
||||
* |
||||
* The function can be used after a call to @c dThreadingImplementationShutdownProcessing |
||||
* to make sure all the threads have already been released by threading implementation
|
||||
* and it can be deleted or it can be cleaned up for restart and served by another pool |
||||
* or this pool's threads can be used to serve another threading implementation. |
||||
* |
||||
* Note that is it not necessary to call this function before pool destruction |
||||
* since @c dThreadingFreeThreadPool performs similar wait operation implicitly on its own. |
||||
*
|
||||
* It is OK to call this function even if pool was not serving any threading implementation |
||||
* in which case the call exits immediately with minimal delay. |
||||
*
|
||||
* @param pool Thread pool ID to wait for |
||||
* |
||||
* @ingroup threading |
||||
* @see dThreadingAllocateThreadPool |
||||
* @see dThreadingImplementationShutdownProcessing |
||||
* @see dThreadingFreeThreadPool |
||||
*/ |
||||
ODE_API void dThreadingThreadPoolWaitIdleState(dThreadingThreadPoolID pool); |
||||
|
||||
/**
|
||||
* @brief Deletes a built-in thread pool instance. |
||||
* |
||||
* The pool threads must be released from any implementations they might be serving |
||||
* before this function is called. Otherwise the call is going to block
|
||||
* and wait until pool's threads return. |
||||
*
|
||||
* @param pool Thread pool ID to delete |
||||
* |
||||
* @ingroup threading |
||||
* @see dThreadingAllocateThreadPool |
||||
* @see dThreadingImplementationShutdownProcessing |
||||
*/ |
||||
ODE_API void dThreadingFreeThreadPool(dThreadingThreadPoolID pool); |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif /* #ifndef _ODE_THREADING_IMPL_H_ */ |
||||
@ -0,0 +1,76 @@ |
||||
/*************************************************************************
|
||||
* * |
||||
* Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * |
||||
* All rights reserved. Email: russ@q12.org Web: www.q12.org * |
||||
* * |
||||
* This library is free software; you can redistribute it and/or * |
||||
* modify it under the terms of EITHER: * |
||||
* (1) The GNU Lesser General Public License as published by the Free * |
||||
* Software Foundation; either version 2.1 of the License, or (at * |
||||
* your option) any later version. The text of the GNU Lesser * |
||||
* General Public License is included with this library in the * |
||||
* file LICENSE.TXT. * |
||||
* (2) The BSD-style license that is included with this library in * |
||||
* the file LICENSE-BSD.TXT. * |
||||
* * |
||||
* This library is distributed in the hope that it will be useful, * |
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of * |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * |
||||
* LICENSE.TXT and LICENSE-BSD.TXT for more details. * |
||||
* * |
||||
*************************************************************************/ |
||||
|
||||
#ifndef _ODE_TIMER_H_ |
||||
#define _ODE_TIMER_H_ |
||||
|
||||
#include <ode/odeconfig.h> |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
/* stop watch objects */ |
||||
|
||||
typedef struct dStopwatch { |
||||
double time; /* total clock count */ |
||||
unsigned long cc[2]; /* clock count since last `start' */ |
||||
} dStopwatch; |
||||
|
||||
ODE_API void dStopwatchReset (dStopwatch *); |
||||
ODE_API void dStopwatchStart (dStopwatch *); |
||||
ODE_API void dStopwatchStop (dStopwatch *); |
||||
ODE_API double dStopwatchTime (dStopwatch *); /* returns total time in secs */ |
||||
|
||||
|
||||
/* code timers */ |
||||
|
||||
ODE_API void dTimerStart (const char *description); /* pass a static string here */ |
||||
ODE_API void dTimerNow (const char *description); /* pass a static string here */ |
||||
ODE_API void dTimerEnd(void); |
||||
|
||||
/* print out a timer report. if `average' is nonzero, print out the average
|
||||
* time for each slot (this is only meaningful if the same start-now-end |
||||
* calls are being made repeatedly. |
||||
*/ |
||||
ODE_API void dTimerReport (FILE *fout, int average); |
||||
|
||||
|
||||
/* resolution */ |
||||
|
||||
/* returns the timer ticks per second implied by the timing hardware or API.
|
||||
* the actual timer resolution may not be this great. |
||||
*/ |
||||
ODE_API double dTimerTicksPerSecond(void); |
||||
|
||||
/* returns an estimate of the actual timer resolution, in seconds. this may
|
||||
* be greater than 1/ticks_per_second. |
||||
*/ |
||||
ODE_API double dTimerResolution(void); |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif |
||||
@ -0,0 +1,6 @@ |
||||
#ifndef _ODE_VERSION_H_ |
||||
#define _ODE_VERSION_H_ |
||||
|
||||
#define dODE_VERSION "0.16.0" |
||||
|
||||
#endif |
||||
@ -0,0 +1,6 @@ |
||||
#ifndef _ODE_VERSION_H_ |
||||
#define _ODE_VERSION_H_ |
||||
|
||||
#define dODE_VERSION "@ODE_VERSION@" |
||||
|
||||
#endif |
||||
@ -0,0 +1,135 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL.h |
||||
* |
||||
* Main include header for the SDL library |
||||
*/ |
||||
|
||||
|
||||
#ifndef SDL_h_ |
||||
#define SDL_h_ |
||||
|
||||
#include "SDL_main.h" |
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_assert.h" |
||||
#include "SDL_atomic.h" |
||||
#include "SDL_audio.h" |
||||
#include "SDL_clipboard.h" |
||||
#include "SDL_cpuinfo.h" |
||||
#include "SDL_endian.h" |
||||
#include "SDL_error.h" |
||||
#include "SDL_events.h" |
||||
#include "SDL_filesystem.h" |
||||
#include "SDL_gamecontroller.h" |
||||
#include "SDL_haptic.h" |
||||
#include "SDL_hints.h" |
||||
#include "SDL_joystick.h" |
||||
#include "SDL_loadso.h" |
||||
#include "SDL_log.h" |
||||
#include "SDL_messagebox.h" |
||||
#include "SDL_mutex.h" |
||||
#include "SDL_power.h" |
||||
#include "SDL_render.h" |
||||
#include "SDL_rwops.h" |
||||
#include "SDL_sensor.h" |
||||
#include "SDL_shape.h" |
||||
#include "SDL_system.h" |
||||
#include "SDL_thread.h" |
||||
#include "SDL_timer.h" |
||||
#include "SDL_version.h" |
||||
#include "SDL_video.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* As of version 0.5, SDL is loaded dynamically into the application */ |
||||
|
||||
/**
|
||||
* \name SDL_INIT_* |
||||
* |
||||
* These are the flags which may be passed to SDL_Init(). You should |
||||
* specify the subsystems which you will be using in your application. |
||||
*/ |
||||
/* @{ */ |
||||
#define SDL_INIT_TIMER 0x00000001u |
||||
#define SDL_INIT_AUDIO 0x00000010u |
||||
#define SDL_INIT_VIDEO 0x00000020u /**< SDL_INIT_VIDEO implies SDL_INIT_EVENTS */ |
||||
#define SDL_INIT_JOYSTICK 0x00000200u /**< SDL_INIT_JOYSTICK implies SDL_INIT_EVENTS */ |
||||
#define SDL_INIT_HAPTIC 0x00001000u |
||||
#define SDL_INIT_GAMECONTROLLER 0x00002000u /**< SDL_INIT_GAMECONTROLLER implies SDL_INIT_JOYSTICK */ |
||||
#define SDL_INIT_EVENTS 0x00004000u |
||||
#define SDL_INIT_SENSOR 0x00008000u |
||||
#define SDL_INIT_NOPARACHUTE 0x00100000u /**< compatibility; this flag is ignored. */ |
||||
#define SDL_INIT_EVERYTHING ( \ |
||||
SDL_INIT_TIMER | SDL_INIT_AUDIO | SDL_INIT_VIDEO | SDL_INIT_EVENTS | \
|
||||
SDL_INIT_JOYSTICK | SDL_INIT_HAPTIC | SDL_INIT_GAMECONTROLLER | SDL_INIT_SENSOR \
|
||||
) |
||||
/* @} */ |
||||
|
||||
/**
|
||||
* This function initializes the subsystems specified by \c flags |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_Init(Uint32 flags); |
||||
|
||||
/**
|
||||
* This function initializes specific SDL subsystems |
||||
* |
||||
* Subsystem initialization is ref-counted, you must call |
||||
* SDL_QuitSubSystem() for each SDL_InitSubSystem() to correctly |
||||
* shutdown a subsystem manually (or call SDL_Quit() to force shutdown). |
||||
* If a subsystem is already loaded then this call will |
||||
* increase the ref-count and return. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_InitSubSystem(Uint32 flags); |
||||
|
||||
/**
|
||||
* This function cleans up specific SDL subsystems |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_QuitSubSystem(Uint32 flags); |
||||
|
||||
/**
|
||||
* This function returns a mask of the specified subsystems which have |
||||
* previously been initialized. |
||||
* |
||||
* If \c flags is 0, it returns a mask of all initialized subsystems. |
||||
*/ |
||||
extern DECLSPEC Uint32 SDLCALL SDL_WasInit(Uint32 flags); |
||||
|
||||
/**
|
||||
* This function cleans up all initialized subsystems. You should |
||||
* call it upon all exit conditions. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_Quit(void); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,291 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
#ifndef SDL_assert_h_ |
||||
#define SDL_assert_h_ |
||||
|
||||
#include "SDL_config.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
#ifndef SDL_ASSERT_LEVEL |
||||
#ifdef SDL_DEFAULT_ASSERT_LEVEL |
||||
#define SDL_ASSERT_LEVEL SDL_DEFAULT_ASSERT_LEVEL |
||||
#elif defined(_DEBUG) || defined(DEBUG) || \ |
||||
(defined(__GNUC__) && !defined(__OPTIMIZE__)) |
||||
#define SDL_ASSERT_LEVEL 2 |
||||
#else |
||||
#define SDL_ASSERT_LEVEL 1 |
||||
#endif |
||||
#endif /* SDL_ASSERT_LEVEL */ |
||||
|
||||
/*
|
||||
These are macros and not first class functions so that the debugger breaks |
||||
on the assertion line and not in some random guts of SDL, and so each |
||||
assert can have unique static variables associated with it. |
||||
*/ |
||||
|
||||
#if defined(_MSC_VER) |
||||
/* Don't include intrin.h here because it contains C++ code */ |
||||
extern void __cdecl __debugbreak(void); |
||||
#define SDL_TriggerBreakpoint() __debugbreak() |
||||
#elif ( (!defined(__NACL__)) && ((defined(__GNUC__) || defined(__clang__)) && (defined(__i386__) || defined(__x86_64__))) ) |
||||
#define SDL_TriggerBreakpoint() __asm__ __volatile__ ( "int $3\n\t" ) |
||||
#elif defined(__386__) && defined(__WATCOMC__) |
||||
#define SDL_TriggerBreakpoint() { _asm { int 0x03 } } |
||||
#elif defined(HAVE_SIGNAL_H) && !defined(__WATCOMC__) |
||||
#include <signal.h> |
||||
#define SDL_TriggerBreakpoint() raise(SIGTRAP) |
||||
#else |
||||
/* How do we trigger breakpoints on this platform? */ |
||||
#define SDL_TriggerBreakpoint() |
||||
#endif |
||||
|
||||
#if defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 199901L) /* C99 supports __func__ as a standard. */ |
||||
# define SDL_FUNCTION __func__ |
||||
#elif ((__GNUC__ >= 2) || defined(_MSC_VER) || defined (__WATCOMC__)) |
||||
# define SDL_FUNCTION __FUNCTION__ |
||||
#else |
||||
# define SDL_FUNCTION "???" |
||||
#endif |
||||
#define SDL_FILE __FILE__ |
||||
#define SDL_LINE __LINE__ |
||||
|
||||
/*
|
||||
sizeof (x) makes the compiler still parse the expression even without |
||||
assertions enabled, so the code is always checked at compile time, but |
||||
doesn't actually generate code for it, so there are no side effects or |
||||
expensive checks at run time, just the constant size of what x WOULD be, |
||||
which presumably gets optimized out as unused. |
||||
This also solves the problem of... |
||||
|
||||
int somevalue = blah(); |
||||
SDL_assert(somevalue == 1); |
||||
|
||||
...which would cause compiles to complain that somevalue is unused if we |
||||
disable assertions. |
||||
*/ |
||||
|
||||
/* "while (0,0)" fools Microsoft's compiler's /W4 warning level into thinking
|
||||
this condition isn't constant. And looks like an owl's face! */ |
||||
#ifdef _MSC_VER /* stupid /W4 warnings. */ |
||||
#define SDL_NULL_WHILE_LOOP_CONDITION (0,0) |
||||
#else |
||||
#define SDL_NULL_WHILE_LOOP_CONDITION (0) |
||||
#endif |
||||
|
||||
#define SDL_disabled_assert(condition) \ |
||||
do { (void) sizeof ((condition)); } while (SDL_NULL_WHILE_LOOP_CONDITION) |
||||
|
||||
typedef enum |
||||
{ |
||||
SDL_ASSERTION_RETRY, /**< Retry the assert immediately. */ |
||||
SDL_ASSERTION_BREAK, /**< Make the debugger trigger a breakpoint. */ |
||||
SDL_ASSERTION_ABORT, /**< Terminate the program. */ |
||||
SDL_ASSERTION_IGNORE, /**< Ignore the assert. */ |
||||
SDL_ASSERTION_ALWAYS_IGNORE /**< Ignore the assert from now on. */ |
||||
} SDL_AssertState; |
||||
|
||||
typedef struct SDL_AssertData |
||||
{ |
||||
int always_ignore; |
||||
unsigned int trigger_count; |
||||
const char *condition; |
||||
const char *filename; |
||||
int linenum; |
||||
const char *function; |
||||
const struct SDL_AssertData *next; |
||||
} SDL_AssertData; |
||||
|
||||
#if (SDL_ASSERT_LEVEL > 0) |
||||
|
||||
/* Never call this directly. Use the SDL_assert* macros. */ |
||||
extern DECLSPEC SDL_AssertState SDLCALL SDL_ReportAssertion(SDL_AssertData *, |
||||
const char *, |
||||
const char *, int) |
||||
#if defined(__clang__) |
||||
#if __has_feature(attribute_analyzer_noreturn) |
||||
/* this tells Clang's static analysis that we're a custom assert function,
|
||||
and that the analyzer should assume the condition was always true past this |
||||
SDL_assert test. */ |
||||
__attribute__((analyzer_noreturn)) |
||||
#endif |
||||
#endif |
||||
; |
||||
|
||||
/* the do {} while(0) avoids dangling else problems:
|
||||
if (x) SDL_assert(y); else blah(); |
||||
... without the do/while, the "else" could attach to this macro's "if". |
||||
We try to handle just the minimum we need here in a macro...the loop, |
||||
the static vars, and break points. The heavy lifting is handled in |
||||
SDL_ReportAssertion(), in SDL_assert.c. |
||||
*/ |
||||
#define SDL_enabled_assert(condition) \ |
||||
do { \
|
||||
while ( !(condition) ) { \
|
||||
static struct SDL_AssertData sdl_assert_data = { \
|
||||
0, 0, #condition, 0, 0, 0, 0 \
|
||||
}; \
|
||||
const SDL_AssertState sdl_assert_state = SDL_ReportAssertion(&sdl_assert_data, SDL_FUNCTION, SDL_FILE, SDL_LINE); \
|
||||
if (sdl_assert_state == SDL_ASSERTION_RETRY) { \
|
||||
continue; /* go again. */ \
|
||||
} else if (sdl_assert_state == SDL_ASSERTION_BREAK) { \
|
||||
SDL_TriggerBreakpoint(); \
|
||||
} \
|
||||
break; /* not retrying. */ \
|
||||
} \
|
||||
} while (SDL_NULL_WHILE_LOOP_CONDITION) |
||||
|
||||
#endif /* enabled assertions support code */ |
||||
|
||||
/* Enable various levels of assertions. */ |
||||
#if SDL_ASSERT_LEVEL == 0 /* assertions disabled */ |
||||
# define SDL_assert(condition) SDL_disabled_assert(condition) |
||||
# define SDL_assert_release(condition) SDL_disabled_assert(condition) |
||||
# define SDL_assert_paranoid(condition) SDL_disabled_assert(condition) |
||||
#elif SDL_ASSERT_LEVEL == 1 /* release settings. */ |
||||
# define SDL_assert(condition) SDL_disabled_assert(condition) |
||||
# define SDL_assert_release(condition) SDL_enabled_assert(condition) |
||||
# define SDL_assert_paranoid(condition) SDL_disabled_assert(condition) |
||||
#elif SDL_ASSERT_LEVEL == 2 /* normal settings. */ |
||||
# define SDL_assert(condition) SDL_enabled_assert(condition) |
||||
# define SDL_assert_release(condition) SDL_enabled_assert(condition) |
||||
# define SDL_assert_paranoid(condition) SDL_disabled_assert(condition) |
||||
#elif SDL_ASSERT_LEVEL == 3 /* paranoid settings. */ |
||||
# define SDL_assert(condition) SDL_enabled_assert(condition) |
||||
# define SDL_assert_release(condition) SDL_enabled_assert(condition) |
||||
# define SDL_assert_paranoid(condition) SDL_enabled_assert(condition) |
||||
#else |
||||
# error Unknown assertion level. |
||||
#endif |
||||
|
||||
/* this assertion is never disabled at any level. */ |
||||
#define SDL_assert_always(condition) SDL_enabled_assert(condition) |
||||
|
||||
|
||||
typedef SDL_AssertState (SDLCALL *SDL_AssertionHandler)( |
||||
const SDL_AssertData* data, void* userdata); |
||||
|
||||
/**
|
||||
* \brief Set an application-defined assertion handler. |
||||
* |
||||
* This allows an app to show its own assertion UI and/or force the |
||||
* response to an assertion failure. If the app doesn't provide this, SDL |
||||
* will try to do the right thing, popping up a system-specific GUI dialog, |
||||
* and probably minimizing any fullscreen windows. |
||||
* |
||||
* This callback may fire from any thread, but it runs wrapped in a mutex, so |
||||
* it will only fire from one thread at a time. |
||||
* |
||||
* Setting the callback to NULL restores SDL's original internal handler. |
||||
* |
||||
* This callback is NOT reset to SDL's internal handler upon SDL_Quit()! |
||||
* |
||||
* Return SDL_AssertState value of how to handle the assertion failure. |
||||
* |
||||
* \param handler Callback function, called when an assertion fails. |
||||
* \param userdata A pointer passed to the callback as-is. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_SetAssertionHandler( |
||||
SDL_AssertionHandler handler, |
||||
void *userdata); |
||||
|
||||
/**
|
||||
* \brief Get the default assertion handler. |
||||
* |
||||
* This returns the function pointer that is called by default when an |
||||
* assertion is triggered. This is an internal function provided by SDL, |
||||
* that is used for assertions when SDL_SetAssertionHandler() hasn't been |
||||
* used to provide a different function. |
||||
* |
||||
* \return The default SDL_AssertionHandler that is called when an assert triggers. |
||||
*/ |
||||
extern DECLSPEC SDL_AssertionHandler SDLCALL SDL_GetDefaultAssertionHandler(void); |
||||
|
||||
/**
|
||||
* \brief Get the current assertion handler. |
||||
* |
||||
* This returns the function pointer that is called when an assertion is |
||||
* triggered. This is either the value last passed to |
||||
* SDL_SetAssertionHandler(), or if no application-specified function is |
||||
* set, is equivalent to calling SDL_GetDefaultAssertionHandler(). |
||||
* |
||||
* \param puserdata Pointer to a void*, which will store the "userdata" |
||||
* pointer that was passed to SDL_SetAssertionHandler(). |
||||
* This value will always be NULL for the default handler. |
||||
* If you don't care about this data, it is safe to pass |
||||
* a NULL pointer to this function to ignore it. |
||||
* \return The SDL_AssertionHandler that is called when an assert triggers. |
||||
*/ |
||||
extern DECLSPEC SDL_AssertionHandler SDLCALL SDL_GetAssertionHandler(void **puserdata); |
||||
|
||||
/**
|
||||
* \brief Get a list of all assertion failures. |
||||
* |
||||
* Get all assertions triggered since last call to SDL_ResetAssertionReport(), |
||||
* or the start of the program. |
||||
* |
||||
* The proper way to examine this data looks something like this: |
||||
* |
||||
* <code> |
||||
* const SDL_AssertData *item = SDL_GetAssertionReport(); |
||||
* while (item) { |
||||
* printf("'%s', %s (%s:%d), triggered %u times, always ignore: %s.\\n", |
||||
* item->condition, item->function, item->filename, |
||||
* item->linenum, item->trigger_count, |
||||
* item->always_ignore ? "yes" : "no"); |
||||
* item = item->next; |
||||
* } |
||||
* </code> |
||||
* |
||||
* \return List of all assertions. |
||||
* \sa SDL_ResetAssertionReport |
||||
*/ |
||||
extern DECLSPEC const SDL_AssertData * SDLCALL SDL_GetAssertionReport(void); |
||||
|
||||
/**
|
||||
* \brief Reset the list of all assertion failures. |
||||
* |
||||
* Reset list of all assertions triggered. |
||||
* |
||||
* \sa SDL_GetAssertionReport |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_ResetAssertionReport(void); |
||||
|
||||
|
||||
/* these had wrong naming conventions until 2.0.4. Please update your app! */ |
||||
#define SDL_assert_state SDL_AssertState |
||||
#define SDL_assert_data SDL_AssertData |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_assert_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,295 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_atomic.h |
||||
* |
||||
* Atomic operations. |
||||
* |
||||
* IMPORTANT: |
||||
* If you are not an expert in concurrent lockless programming, you should |
||||
* only be using the atomic lock and reference counting functions in this |
||||
* file. In all other cases you should be protecting your data structures |
||||
* with full mutexes. |
||||
* |
||||
* The list of "safe" functions to use are: |
||||
* SDL_AtomicLock() |
||||
* SDL_AtomicUnlock() |
||||
* SDL_AtomicIncRef() |
||||
* SDL_AtomicDecRef() |
||||
* |
||||
* Seriously, here be dragons! |
||||
* ^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
||||
* |
||||
* You can find out a little more about lockless programming and the |
||||
* subtle issues that can arise here: |
||||
* http://msdn.microsoft.com/en-us/library/ee418650%28v=vs.85%29.aspx
|
||||
* |
||||
* There's also lots of good information here: |
||||
* http://www.1024cores.net/home/lock-free-algorithms
|
||||
* http://preshing.com/
|
||||
* |
||||
* These operations may or may not actually be implemented using |
||||
* processor specific atomic operations. When possible they are |
||||
* implemented as true processor specific atomic operations. When that |
||||
* is not possible the are implemented using locks that *do* use the |
||||
* available atomic operations. |
||||
* |
||||
* All of the atomic operations that modify memory are full memory barriers. |
||||
*/ |
||||
|
||||
#ifndef SDL_atomic_h_ |
||||
#define SDL_atomic_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_platform.h" |
||||
|
||||
#include "begin_code.h" |
||||
|
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \name SDL AtomicLock |
||||
* |
||||
* The atomic locks are efficient spinlocks using CPU instructions, |
||||
* but are vulnerable to starvation and can spin forever if a thread |
||||
* holding a lock has been terminated. For this reason you should |
||||
* minimize the code executed inside an atomic lock and never do |
||||
* expensive things like API or system calls while holding them. |
||||
* |
||||
* The atomic locks are not safe to lock recursively. |
||||
* |
||||
* Porting Note: |
||||
* The spin lock functions and type are required and can not be |
||||
* emulated because they are used in the atomic emulation code. |
||||
*/ |
||||
/* @{ */ |
||||
|
||||
typedef int SDL_SpinLock; |
||||
|
||||
/**
|
||||
* \brief Try to lock a spin lock by setting it to a non-zero value. |
||||
* |
||||
* \param lock Points to the lock. |
||||
* |
||||
* \return SDL_TRUE if the lock succeeded, SDL_FALSE if the lock is already held. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_AtomicTryLock(SDL_SpinLock *lock); |
||||
|
||||
/**
|
||||
* \brief Lock a spin lock by setting it to a non-zero value. |
||||
* |
||||
* \param lock Points to the lock. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_AtomicLock(SDL_SpinLock *lock); |
||||
|
||||
/**
|
||||
* \brief Unlock a spin lock by setting it to 0. Always returns immediately |
||||
* |
||||
* \param lock Points to the lock. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_AtomicUnlock(SDL_SpinLock *lock); |
||||
|
||||
/* @} *//* SDL AtomicLock */ |
||||
|
||||
|
||||
/**
|
||||
* The compiler barrier prevents the compiler from reordering |
||||
* reads and writes to globally visible variables across the call. |
||||
*/ |
||||
#if defined(_MSC_VER) && (_MSC_VER > 1200) && !defined(__clang__) |
||||
void _ReadWriteBarrier(void); |
||||
#pragma intrinsic(_ReadWriteBarrier) |
||||
#define SDL_CompilerBarrier() _ReadWriteBarrier() |
||||
#elif (defined(__GNUC__) && !defined(__EMSCRIPTEN__)) || (defined(__SUNPRO_C) && (__SUNPRO_C >= 0x5120)) |
||||
/* This is correct for all CPUs when using GCC or Solaris Studio 12.1+. */ |
||||
#define SDL_CompilerBarrier() __asm__ __volatile__ ("" : : : "memory") |
||||
#elif defined(__WATCOMC__) |
||||
extern _inline void SDL_CompilerBarrier (void); |
||||
#pragma aux SDL_CompilerBarrier = "" parm [] modify exact []; |
||||
#else |
||||
#define SDL_CompilerBarrier() \ |
||||
{ SDL_SpinLock _tmp = 0; SDL_AtomicLock(&_tmp); SDL_AtomicUnlock(&_tmp); } |
||||
#endif |
||||
|
||||
/**
|
||||
* Memory barriers are designed to prevent reads and writes from being |
||||
* reordered by the compiler and being seen out of order on multi-core CPUs. |
||||
* |
||||
* A typical pattern would be for thread A to write some data and a flag, |
||||
* and for thread B to read the flag and get the data. In this case you |
||||
* would insert a release barrier between writing the data and the flag, |
||||
* guaranteeing that the data write completes no later than the flag is |
||||
* written, and you would insert an acquire barrier between reading the |
||||
* flag and reading the data, to ensure that all the reads associated |
||||
* with the flag have completed. |
||||
* |
||||
* In this pattern you should always see a release barrier paired with |
||||
* an acquire barrier and you should gate the data reads/writes with a |
||||
* single flag variable. |
||||
* |
||||
* For more information on these semantics, take a look at the blog post: |
||||
* http://preshing.com/20120913/acquire-and-release-semantics
|
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_MemoryBarrierReleaseFunction(void); |
||||
extern DECLSPEC void SDLCALL SDL_MemoryBarrierAcquireFunction(void); |
||||
|
||||
#if defined(__GNUC__) && (defined(__powerpc__) || defined(__ppc__)) |
||||
#define SDL_MemoryBarrierRelease() __asm__ __volatile__ ("lwsync" : : : "memory") |
||||
#define SDL_MemoryBarrierAcquire() __asm__ __volatile__ ("lwsync" : : : "memory") |
||||
#elif defined(__GNUC__) && defined(__aarch64__) |
||||
#define SDL_MemoryBarrierRelease() __asm__ __volatile__ ("dmb ish" : : : "memory") |
||||
#define SDL_MemoryBarrierAcquire() __asm__ __volatile__ ("dmb ish" : : : "memory") |
||||
#elif defined(__GNUC__) && defined(__arm__) |
||||
#if 0 /* defined(__LINUX__) || defined(__ANDROID__) */
|
||||
/* Information from:
|
||||
https://chromium.googlesource.com/chromium/chromium/+/trunk/base/atomicops_internals_arm_gcc.h#19
|
||||
|
||||
The Linux kernel provides a helper function which provides the right code for a memory barrier, |
||||
hard-coded at address 0xffff0fa0 |
||||
*/ |
||||
typedef void (*SDL_KernelMemoryBarrierFunc)(); |
||||
#define SDL_MemoryBarrierRelease() ((SDL_KernelMemoryBarrierFunc)0xffff0fa0)() |
||||
#define SDL_MemoryBarrierAcquire() ((SDL_KernelMemoryBarrierFunc)0xffff0fa0)() |
||||
#elif 0 /* defined(__QNXNTO__) */ |
||||
#include <sys/cpuinline.h> |
||||
|
||||
#define SDL_MemoryBarrierRelease() __cpu_membarrier() |
||||
#define SDL_MemoryBarrierAcquire() __cpu_membarrier() |
||||
#else |
||||
#if defined(__ARM_ARCH_7__) || defined(__ARM_ARCH_7A__) || defined(__ARM_ARCH_7EM__) || defined(__ARM_ARCH_7R__) || defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7S__) || defined(__ARM_ARCH_8A__) |
||||
#define SDL_MemoryBarrierRelease() __asm__ __volatile__ ("dmb ish" : : : "memory") |
||||
#define SDL_MemoryBarrierAcquire() __asm__ __volatile__ ("dmb ish" : : : "memory") |
||||
#elif defined(__ARM_ARCH_6__) || defined(__ARM_ARCH_6J__) || defined(__ARM_ARCH_6K__) || defined(__ARM_ARCH_6T2__) || defined(__ARM_ARCH_6Z__) || defined(__ARM_ARCH_6ZK__) || defined(__ARM_ARCH_5TE__) |
||||
#ifdef __thumb__ |
||||
/* The mcr instruction isn't available in thumb mode, use real functions */ |
||||
#define SDL_MEMORY_BARRIER_USES_FUNCTION |
||||
#define SDL_MemoryBarrierRelease() SDL_MemoryBarrierReleaseFunction() |
||||
#define SDL_MemoryBarrierAcquire() SDL_MemoryBarrierAcquireFunction() |
||||
#else |
||||
#define SDL_MemoryBarrierRelease() __asm__ __volatile__ ("mcr p15, 0, %0, c7, c10, 5" : : "r"(0) : "memory") |
||||
#define SDL_MemoryBarrierAcquire() __asm__ __volatile__ ("mcr p15, 0, %0, c7, c10, 5" : : "r"(0) : "memory") |
||||
#endif /* __thumb__ */ |
||||
#else |
||||
#define SDL_MemoryBarrierRelease() __asm__ __volatile__ ("" : : : "memory") |
||||
#define SDL_MemoryBarrierAcquire() __asm__ __volatile__ ("" : : : "memory") |
||||
#endif /* __LINUX__ || __ANDROID__ */ |
||||
#endif /* __GNUC__ && __arm__ */ |
||||
#else |
||||
#if (defined(__SUNPRO_C) && (__SUNPRO_C >= 0x5120)) |
||||
/* This is correct for all CPUs on Solaris when using Solaris Studio 12.1+. */ |
||||
#include <mbarrier.h> |
||||
#define SDL_MemoryBarrierRelease() __machine_rel_barrier() |
||||
#define SDL_MemoryBarrierAcquire() __machine_acq_barrier() |
||||
#else |
||||
/* This is correct for the x86 and x64 CPUs, and we'll expand this over time. */ |
||||
#define SDL_MemoryBarrierRelease() SDL_CompilerBarrier() |
||||
#define SDL_MemoryBarrierAcquire() SDL_CompilerBarrier() |
||||
#endif |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief A type representing an atomic integer value. It is a struct |
||||
* so people don't accidentally use numeric operations on it. |
||||
*/ |
||||
typedef struct { int value; } SDL_atomic_t; |
||||
|
||||
/**
|
||||
* \brief Set an atomic variable to a new value if it is currently an old value. |
||||
* |
||||
* \return SDL_TRUE if the atomic variable was set, SDL_FALSE otherwise. |
||||
* |
||||
* \note If you don't know what this function is for, you shouldn't use it! |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_AtomicCAS(SDL_atomic_t *a, int oldval, int newval); |
||||
|
||||
/**
|
||||
* \brief Set an atomic variable to a value. |
||||
* |
||||
* \return The previous value of the atomic variable. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_AtomicSet(SDL_atomic_t *a, int v); |
||||
|
||||
/**
|
||||
* \brief Get the value of an atomic variable |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_AtomicGet(SDL_atomic_t *a); |
||||
|
||||
/**
|
||||
* \brief Add to an atomic variable. |
||||
* |
||||
* \return The previous value of the atomic variable. |
||||
* |
||||
* \note This same style can be used for any number operation |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_AtomicAdd(SDL_atomic_t *a, int v); |
||||
|
||||
/**
|
||||
* \brief Increment an atomic variable used as a reference count. |
||||
*/ |
||||
#ifndef SDL_AtomicIncRef |
||||
#define SDL_AtomicIncRef(a) SDL_AtomicAdd(a, 1) |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief Decrement an atomic variable used as a reference count. |
||||
* |
||||
* \return SDL_TRUE if the variable reached zero after decrementing, |
||||
* SDL_FALSE otherwise |
||||
*/ |
||||
#ifndef SDL_AtomicDecRef |
||||
#define SDL_AtomicDecRef(a) (SDL_AtomicAdd(a, -1) == 1) |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief Set a pointer to a new value if it is currently an old value. |
||||
* |
||||
* \return SDL_TRUE if the pointer was set, SDL_FALSE otherwise. |
||||
* |
||||
* \note If you don't know what this function is for, you shouldn't use it! |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_AtomicCASPtr(void **a, void *oldval, void *newval); |
||||
|
||||
/**
|
||||
* \brief Set a pointer to a value atomically. |
||||
* |
||||
* \return The previous value of the pointer. |
||||
*/ |
||||
extern DECLSPEC void* SDLCALL SDL_AtomicSetPtr(void **a, void* v); |
||||
|
||||
/**
|
||||
* \brief Get the value of a pointer atomically. |
||||
*/ |
||||
extern DECLSPEC void* SDLCALL SDL_AtomicGetPtr(void **a); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_atomic_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,859 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_audio.h |
||||
* |
||||
* Access to the raw audio mixing buffer for the SDL library. |
||||
*/ |
||||
|
||||
#ifndef SDL_audio_h_ |
||||
#define SDL_audio_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
#include "SDL_endian.h" |
||||
#include "SDL_mutex.h" |
||||
#include "SDL_thread.h" |
||||
#include "SDL_rwops.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief Audio format flags. |
||||
* |
||||
* These are what the 16 bits in SDL_AudioFormat currently mean... |
||||
* (Unspecified bits are always zero). |
||||
* |
||||
* \verbatim |
||||
++-----------------------sample is signed if set |
||||
|| |
||||
|| ++-----------sample is bigendian if set |
||||
|| || |
||||
|| || ++---sample is float if set |
||||
|| || || |
||||
|| || || +---sample bit size---+ |
||||
|| || || | | |
||||
15 14 13 12 11 10 09 08 07 06 05 04 03 02 01 00 |
||||
\endverbatim |
||||
* |
||||
* There are macros in SDL 2.0 and later to query these bits. |
||||
*/ |
||||
typedef Uint16 SDL_AudioFormat; |
||||
|
||||
/**
|
||||
* \name Audio flags |
||||
*/ |
||||
/* @{ */ |
||||
|
||||
#define SDL_AUDIO_MASK_BITSIZE (0xFF) |
||||
#define SDL_AUDIO_MASK_DATATYPE (1<<8) |
||||
#define SDL_AUDIO_MASK_ENDIAN (1<<12) |
||||
#define SDL_AUDIO_MASK_SIGNED (1<<15) |
||||
#define SDL_AUDIO_BITSIZE(x) (x & SDL_AUDIO_MASK_BITSIZE) |
||||
#define SDL_AUDIO_ISFLOAT(x) (x & SDL_AUDIO_MASK_DATATYPE) |
||||
#define SDL_AUDIO_ISBIGENDIAN(x) (x & SDL_AUDIO_MASK_ENDIAN) |
||||
#define SDL_AUDIO_ISSIGNED(x) (x & SDL_AUDIO_MASK_SIGNED) |
||||
#define SDL_AUDIO_ISINT(x) (!SDL_AUDIO_ISFLOAT(x)) |
||||
#define SDL_AUDIO_ISLITTLEENDIAN(x) (!SDL_AUDIO_ISBIGENDIAN(x)) |
||||
#define SDL_AUDIO_ISUNSIGNED(x) (!SDL_AUDIO_ISSIGNED(x)) |
||||
|
||||
/**
|
||||
* \name Audio format flags |
||||
* |
||||
* Defaults to LSB byte order. |
||||
*/ |
||||
/* @{ */ |
||||
#define AUDIO_U8 0x0008 /**< Unsigned 8-bit samples */ |
||||
#define AUDIO_S8 0x8008 /**< Signed 8-bit samples */ |
||||
#define AUDIO_U16LSB 0x0010 /**< Unsigned 16-bit samples */ |
||||
#define AUDIO_S16LSB 0x8010 /**< Signed 16-bit samples */ |
||||
#define AUDIO_U16MSB 0x1010 /**< As above, but big-endian byte order */ |
||||
#define AUDIO_S16MSB 0x9010 /**< As above, but big-endian byte order */ |
||||
#define AUDIO_U16 AUDIO_U16LSB |
||||
#define AUDIO_S16 AUDIO_S16LSB |
||||
/* @} */ |
||||
|
||||
/**
|
||||
* \name int32 support |
||||
*/ |
||||
/* @{ */ |
||||
#define AUDIO_S32LSB 0x8020 /**< 32-bit integer samples */ |
||||
#define AUDIO_S32MSB 0x9020 /**< As above, but big-endian byte order */ |
||||
#define AUDIO_S32 AUDIO_S32LSB |
||||
/* @} */ |
||||
|
||||
/**
|
||||
* \name float32 support |
||||
*/ |
||||
/* @{ */ |
||||
#define AUDIO_F32LSB 0x8120 /**< 32-bit floating point samples */ |
||||
#define AUDIO_F32MSB 0x9120 /**< As above, but big-endian byte order */ |
||||
#define AUDIO_F32 AUDIO_F32LSB |
||||
/* @} */ |
||||
|
||||
/**
|
||||
* \name Native audio byte ordering |
||||
*/ |
||||
/* @{ */ |
||||
#if SDL_BYTEORDER == SDL_LIL_ENDIAN |
||||
#define AUDIO_U16SYS AUDIO_U16LSB |
||||
#define AUDIO_S16SYS AUDIO_S16LSB |
||||
#define AUDIO_S32SYS AUDIO_S32LSB |
||||
#define AUDIO_F32SYS AUDIO_F32LSB |
||||
#else |
||||
#define AUDIO_U16SYS AUDIO_U16MSB |
||||
#define AUDIO_S16SYS AUDIO_S16MSB |
||||
#define AUDIO_S32SYS AUDIO_S32MSB |
||||
#define AUDIO_F32SYS AUDIO_F32MSB |
||||
#endif |
||||
/* @} */ |
||||
|
||||
/**
|
||||
* \name Allow change flags |
||||
* |
||||
* Which audio format changes are allowed when opening a device. |
||||
*/ |
||||
/* @{ */ |
||||
#define SDL_AUDIO_ALLOW_FREQUENCY_CHANGE 0x00000001 |
||||
#define SDL_AUDIO_ALLOW_FORMAT_CHANGE 0x00000002 |
||||
#define SDL_AUDIO_ALLOW_CHANNELS_CHANGE 0x00000004 |
||||
#define SDL_AUDIO_ALLOW_SAMPLES_CHANGE 0x00000008 |
||||
#define SDL_AUDIO_ALLOW_ANY_CHANGE (SDL_AUDIO_ALLOW_FREQUENCY_CHANGE|SDL_AUDIO_ALLOW_FORMAT_CHANGE|SDL_AUDIO_ALLOW_CHANNELS_CHANGE|SDL_AUDIO_ALLOW_SAMPLES_CHANGE) |
||||
/* @} */ |
||||
|
||||
/* @} *//* Audio flags */ |
||||
|
||||
/**
|
||||
* This function is called when the audio device needs more data. |
||||
* |
||||
* \param userdata An application-specific parameter saved in |
||||
* the SDL_AudioSpec structure |
||||
* \param stream A pointer to the audio data buffer. |
||||
* \param len The length of that buffer in bytes. |
||||
* |
||||
* Once the callback returns, the buffer will no longer be valid. |
||||
* Stereo samples are stored in a LRLRLR ordering. |
||||
* |
||||
* You can choose to avoid callbacks and use SDL_QueueAudio() instead, if |
||||
* you like. Just open your audio device with a NULL callback. |
||||
*/ |
||||
typedef void (SDLCALL * SDL_AudioCallback) (void *userdata, Uint8 * stream, |
||||
int len); |
||||
|
||||
/**
|
||||
* The calculated values in this structure are calculated by SDL_OpenAudio(). |
||||
* |
||||
* For multi-channel audio, the default SDL channel mapping is: |
||||
* 2: FL FR (stereo) |
||||
* 3: FL FR LFE (2.1 surround) |
||||
* 4: FL FR BL BR (quad) |
||||
* 5: FL FR FC BL BR (quad + center) |
||||
* 6: FL FR FC LFE SL SR (5.1 surround - last two can also be BL BR) |
||||
* 7: FL FR FC LFE BC SL SR (6.1 surround) |
||||
* 8: FL FR FC LFE BL BR SL SR (7.1 surround) |
||||
*/ |
||||
typedef struct SDL_AudioSpec |
||||
{ |
||||
int freq; /**< DSP frequency -- samples per second */ |
||||
SDL_AudioFormat format; /**< Audio data format */ |
||||
Uint8 channels; /**< Number of channels: 1 mono, 2 stereo */ |
||||
Uint8 silence; /**< Audio buffer silence value (calculated) */ |
||||
Uint16 samples; /**< Audio buffer size in sample FRAMES (total samples divided by channel count) */ |
||||
Uint16 padding; /**< Necessary for some compile environments */ |
||||
Uint32 size; /**< Audio buffer size in bytes (calculated) */ |
||||
SDL_AudioCallback callback; /**< Callback that feeds the audio device (NULL to use SDL_QueueAudio()). */ |
||||
void *userdata; /**< Userdata passed to callback (ignored for NULL callbacks). */ |
||||
} SDL_AudioSpec; |
||||
|
||||
|
||||
struct SDL_AudioCVT; |
||||
typedef void (SDLCALL * SDL_AudioFilter) (struct SDL_AudioCVT * cvt, |
||||
SDL_AudioFormat format); |
||||
|
||||
/**
|
||||
* \brief Upper limit of filters in SDL_AudioCVT |
||||
* |
||||
* The maximum number of SDL_AudioFilter functions in SDL_AudioCVT is |
||||
* currently limited to 9. The SDL_AudioCVT.filters array has 10 pointers, |
||||
* one of which is the terminating NULL pointer. |
||||
*/ |
||||
#define SDL_AUDIOCVT_MAX_FILTERS 9 |
||||
|
||||
/**
|
||||
* \struct SDL_AudioCVT |
||||
* \brief A structure to hold a set of audio conversion filters and buffers. |
||||
* |
||||
* Note that various parts of the conversion pipeline can take advantage |
||||
* of SIMD operations (like SSE2, for example). SDL_AudioCVT doesn't require |
||||
* you to pass it aligned data, but can possibly run much faster if you |
||||
* set both its (buf) field to a pointer that is aligned to 16 bytes, and its |
||||
* (len) field to something that's a multiple of 16, if possible. |
||||
*/ |
||||
#ifdef __GNUC__ |
||||
/* This structure is 84 bytes on 32-bit architectures, make sure GCC doesn't
|
||||
pad it out to 88 bytes to guarantee ABI compatibility between compilers. |
||||
vvv |
||||
The next time we rev the ABI, make sure to size the ints and add padding. |
||||
*/ |
||||
#define SDL_AUDIOCVT_PACKED __attribute__((packed)) |
||||
#else |
||||
#define SDL_AUDIOCVT_PACKED |
||||
#endif |
||||
/* */ |
||||
typedef struct SDL_AudioCVT |
||||
{ |
||||
int needed; /**< Set to 1 if conversion possible */ |
||||
SDL_AudioFormat src_format; /**< Source audio format */ |
||||
SDL_AudioFormat dst_format; /**< Target audio format */ |
||||
double rate_incr; /**< Rate conversion increment */ |
||||
Uint8 *buf; /**< Buffer to hold entire audio data */ |
||||
int len; /**< Length of original audio buffer */ |
||||
int len_cvt; /**< Length of converted audio buffer */ |
||||
int len_mult; /**< buffer must be len*len_mult big */ |
||||
double len_ratio; /**< Given len, final size is len*len_ratio */ |
||||
SDL_AudioFilter filters[SDL_AUDIOCVT_MAX_FILTERS + 1]; /**< NULL-terminated list of filter functions */ |
||||
int filter_index; /**< Current audio conversion function */ |
||||
} SDL_AUDIOCVT_PACKED SDL_AudioCVT; |
||||
|
||||
|
||||
/* Function prototypes */ |
||||
|
||||
/**
|
||||
* \name Driver discovery functions |
||||
* |
||||
* These functions return the list of built in audio drivers, in the |
||||
* order that they are normally initialized by default. |
||||
*/ |
||||
/* @{ */ |
||||
extern DECLSPEC int SDLCALL SDL_GetNumAudioDrivers(void); |
||||
extern DECLSPEC const char *SDLCALL SDL_GetAudioDriver(int index); |
||||
/* @} */ |
||||
|
||||
/**
|
||||
* \name Initialization and cleanup |
||||
* |
||||
* \internal These functions are used internally, and should not be used unless |
||||
* you have a specific need to specify the audio driver you want to |
||||
* use. You should normally use SDL_Init() or SDL_InitSubSystem(). |
||||
*/ |
||||
/* @{ */ |
||||
extern DECLSPEC int SDLCALL SDL_AudioInit(const char *driver_name); |
||||
extern DECLSPEC void SDLCALL SDL_AudioQuit(void); |
||||
/* @} */ |
||||
|
||||
/**
|
||||
* This function returns the name of the current audio driver, or NULL |
||||
* if no driver has been initialized. |
||||
*/ |
||||
extern DECLSPEC const char *SDLCALL SDL_GetCurrentAudioDriver(void); |
||||
|
||||
/**
|
||||
* This function opens the audio device with the desired parameters, and |
||||
* returns 0 if successful, placing the actual hardware parameters in the |
||||
* structure pointed to by \c obtained. If \c obtained is NULL, the audio |
||||
* data passed to the callback function will be guaranteed to be in the |
||||
* requested format, and will be automatically converted to the hardware |
||||
* audio format if necessary. This function returns -1 if it failed |
||||
* to open the audio device, or couldn't set up the audio thread. |
||||
* |
||||
* When filling in the desired audio spec structure, |
||||
* - \c desired->freq should be the desired audio frequency in samples-per- |
||||
* second. |
||||
* - \c desired->format should be the desired audio format. |
||||
* - \c desired->samples is the desired size of the audio buffer, in |
||||
* samples. This number should be a power of two, and may be adjusted by |
||||
* the audio driver to a value more suitable for the hardware. Good values |
||||
* seem to range between 512 and 8096 inclusive, depending on the |
||||
* application and CPU speed. Smaller values yield faster response time, |
||||
* but can lead to underflow if the application is doing heavy processing |
||||
* and cannot fill the audio buffer in time. A stereo sample consists of |
||||
* both right and left channels in LR ordering. |
||||
* Note that the number of samples is directly related to time by the |
||||
* following formula: \code ms = (samples*1000)/freq \endcode |
||||
* - \c desired->size is the size in bytes of the audio buffer, and is |
||||
* calculated by SDL_OpenAudio(). |
||||
* - \c desired->silence is the value used to set the buffer to silence, |
||||
* and is calculated by SDL_OpenAudio(). |
||||
* - \c desired->callback should be set to a function that will be called |
||||
* when the audio device is ready for more data. It is passed a pointer |
||||
* to the audio buffer, and the length in bytes of the audio buffer. |
||||
* This function usually runs in a separate thread, and so you should |
||||
* protect data structures that it accesses by calling SDL_LockAudio() |
||||
* and SDL_UnlockAudio() in your code. Alternately, you may pass a NULL |
||||
* pointer here, and call SDL_QueueAudio() with some frequency, to queue |
||||
* more audio samples to be played (or for capture devices, call |
||||
* SDL_DequeueAudio() with some frequency, to obtain audio samples). |
||||
* - \c desired->userdata is passed as the first parameter to your callback |
||||
* function. If you passed a NULL callback, this value is ignored. |
||||
* |
||||
* The audio device starts out playing silence when it's opened, and should |
||||
* be enabled for playing by calling \c SDL_PauseAudio(0) when you are ready |
||||
* for your audio callback function to be called. Since the audio driver |
||||
* may modify the requested size of the audio buffer, you should allocate |
||||
* any local mixing buffers after you open the audio device. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_OpenAudio(SDL_AudioSpec * desired, |
||||
SDL_AudioSpec * obtained); |
||||
|
||||
/**
|
||||
* SDL Audio Device IDs. |
||||
* |
||||
* A successful call to SDL_OpenAudio() is always device id 1, and legacy |
||||
* SDL audio APIs assume you want this device ID. SDL_OpenAudioDevice() calls |
||||
* always returns devices >= 2 on success. The legacy calls are good both |
||||
* for backwards compatibility and when you don't care about multiple, |
||||
* specific, or capture devices. |
||||
*/ |
||||
typedef Uint32 SDL_AudioDeviceID; |
||||
|
||||
/**
|
||||
* Get the number of available devices exposed by the current driver. |
||||
* Only valid after a successfully initializing the audio subsystem. |
||||
* Returns -1 if an explicit list of devices can't be determined; this is |
||||
* not an error. For example, if SDL is set up to talk to a remote audio |
||||
* server, it can't list every one available on the Internet, but it will |
||||
* still allow a specific host to be specified to SDL_OpenAudioDevice(). |
||||
* |
||||
* In many common cases, when this function returns a value <= 0, it can still |
||||
* successfully open the default device (NULL for first argument of |
||||
* SDL_OpenAudioDevice()). |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GetNumAudioDevices(int iscapture); |
||||
|
||||
/**
|
||||
* Get the human-readable name of a specific audio device. |
||||
* Must be a value between 0 and (number of audio devices-1). |
||||
* Only valid after a successfully initializing the audio subsystem. |
||||
* The values returned by this function reflect the latest call to |
||||
* SDL_GetNumAudioDevices(); recall that function to redetect available |
||||
* hardware. |
||||
* |
||||
* The string returned by this function is UTF-8 encoded, read-only, and |
||||
* managed internally. You are not to free it. If you need to keep the |
||||
* string for any length of time, you should make your own copy of it, as it |
||||
* will be invalid next time any of several other SDL functions is called. |
||||
*/ |
||||
extern DECLSPEC const char *SDLCALL SDL_GetAudioDeviceName(int index, |
||||
int iscapture); |
||||
|
||||
|
||||
/**
|
||||
* Open a specific audio device. Passing in a device name of NULL requests |
||||
* the most reasonable default (and is equivalent to calling SDL_OpenAudio()). |
||||
* |
||||
* The device name is a UTF-8 string reported by SDL_GetAudioDeviceName(), but |
||||
* some drivers allow arbitrary and driver-specific strings, such as a |
||||
* hostname/IP address for a remote audio server, or a filename in the |
||||
* diskaudio driver. |
||||
* |
||||
* \return 0 on error, a valid device ID that is >= 2 on success. |
||||
* |
||||
* SDL_OpenAudio(), unlike this function, always acts on device ID 1. |
||||
*/ |
||||
extern DECLSPEC SDL_AudioDeviceID SDLCALL SDL_OpenAudioDevice(const char |
||||
*device, |
||||
int iscapture, |
||||
const |
||||
SDL_AudioSpec * |
||||
desired, |
||||
SDL_AudioSpec * |
||||
obtained, |
||||
int |
||||
allowed_changes); |
||||
|
||||
|
||||
|
||||
/**
|
||||
* \name Audio state |
||||
* |
||||
* Get the current audio state. |
||||
*/ |
||||
/* @{ */ |
||||
typedef enum |
||||
{ |
||||
SDL_AUDIO_STOPPED = 0, |
||||
SDL_AUDIO_PLAYING, |
||||
SDL_AUDIO_PAUSED |
||||
} SDL_AudioStatus; |
||||
extern DECLSPEC SDL_AudioStatus SDLCALL SDL_GetAudioStatus(void); |
||||
|
||||
extern DECLSPEC SDL_AudioStatus SDLCALL |
||||
SDL_GetAudioDeviceStatus(SDL_AudioDeviceID dev); |
||||
/* @} *//* Audio State */ |
||||
|
||||
/**
|
||||
* \name Pause audio functions |
||||
* |
||||
* These functions pause and unpause the audio callback processing. |
||||
* They should be called with a parameter of 0 after opening the audio |
||||
* device to start playing sound. This is so you can safely initialize |
||||
* data for your callback function after opening the audio device. |
||||
* Silence will be written to the audio device during the pause. |
||||
*/ |
||||
/* @{ */ |
||||
extern DECLSPEC void SDLCALL SDL_PauseAudio(int pause_on); |
||||
extern DECLSPEC void SDLCALL SDL_PauseAudioDevice(SDL_AudioDeviceID dev, |
||||
int pause_on); |
||||
/* @} *//* Pause audio functions */ |
||||
|
||||
/**
|
||||
* \brief Load the audio data of a WAVE file into memory |
||||
* |
||||
* Loading a WAVE file requires \c src, \c spec, \c audio_buf and \c audio_len |
||||
* to be valid pointers. The entire data portion of the file is then loaded |
||||
* into memory and decoded if necessary. |
||||
* |
||||
* If \c freesrc is non-zero, the data source gets automatically closed and |
||||
* freed before the function returns. |
||||
* |
||||
* Supported are RIFF WAVE files with the formats PCM (8, 16, 24, and 32 bits), |
||||
* IEEE Float (32 bits), Microsoft ADPCM and IMA ADPCM (4 bits), and A-law and |
||||
* µ-law (8 bits). Other formats are currently unsupported and cause an error. |
||||
* |
||||
* If this function succeeds, the pointer returned by it is equal to \c spec |
||||
* and the pointer to the audio data allocated by the function is written to |
||||
* \c audio_buf and its length in bytes to \c audio_len. The \ref SDL_AudioSpec |
||||
* members \c freq, \c channels, and \c format are set to the values of the |
||||
* audio data in the buffer. The \c samples member is set to a sane default and |
||||
* all others are set to zero. |
||||
* |
||||
* It's necessary to use SDL_FreeWAV() to free the audio data returned in |
||||
* \c audio_buf when it is no longer used. |
||||
* |
||||
* Because of the underspecification of the Waveform format, there are many |
||||
* problematic files in the wild that cause issues with strict decoders. To |
||||
* provide compatibility with these files, this decoder is lenient in regards |
||||
* to the truncation of the file, the fact chunk, and the size of the RIFF |
||||
* chunk. The hints SDL_HINT_WAVE_RIFF_CHUNK_SIZE, SDL_HINT_WAVE_TRUNCATION, |
||||
* and SDL_HINT_WAVE_FACT_CHUNK can be used to tune the behavior of the |
||||
* loading process. |
||||
* |
||||
* Any file that is invalid (due to truncation, corruption, or wrong values in |
||||
* the headers), too big, or unsupported causes an error. Additionally, any |
||||
* critical I/O error from the data source will terminate the loading process |
||||
* with an error. The function returns NULL on error and in all cases (with the |
||||
* exception of \c src being NULL), an appropriate error message will be set. |
||||
* |
||||
* It is required that the data source supports seeking. |
||||
* |
||||
* Example: |
||||
* \code |
||||
* SDL_LoadWAV_RW(SDL_RWFromFile("sample.wav", "rb"), 1, ...); |
||||
* \endcode |
||||
* |
||||
* \param src The data source with the WAVE data |
||||
* \param freesrc A integer value that makes the function close the data source if non-zero |
||||
* \param spec A pointer filled with the audio format of the audio data |
||||
* \param audio_buf A pointer filled with the audio data allocated by the function |
||||
* \param audio_len A pointer filled with the length of the audio data buffer in bytes |
||||
* \return NULL on error, or non-NULL on success. |
||||
*/ |
||||
extern DECLSPEC SDL_AudioSpec *SDLCALL SDL_LoadWAV_RW(SDL_RWops * src, |
||||
int freesrc, |
||||
SDL_AudioSpec * spec, |
||||
Uint8 ** audio_buf, |
||||
Uint32 * audio_len); |
||||
|
||||
/**
|
||||
* Loads a WAV from a file. |
||||
* Compatibility convenience function. |
||||
*/ |
||||
#define SDL_LoadWAV(file, spec, audio_buf, audio_len) \ |
||||
SDL_LoadWAV_RW(SDL_RWFromFile(file, "rb"),1, spec,audio_buf,audio_len) |
||||
|
||||
/**
|
||||
* This function frees data previously allocated with SDL_LoadWAV_RW() |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_FreeWAV(Uint8 * audio_buf); |
||||
|
||||
/**
|
||||
* This function takes a source format and rate and a destination format |
||||
* and rate, and initializes the \c cvt structure with information needed |
||||
* by SDL_ConvertAudio() to convert a buffer of audio data from one format |
||||
* to the other. An unsupported format causes an error and -1 will be returned. |
||||
* |
||||
* \return 0 if no conversion is needed, 1 if the audio filter is set up, |
||||
* or -1 on error. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_BuildAudioCVT(SDL_AudioCVT * cvt, |
||||
SDL_AudioFormat src_format, |
||||
Uint8 src_channels, |
||||
int src_rate, |
||||
SDL_AudioFormat dst_format, |
||||
Uint8 dst_channels, |
||||
int dst_rate); |
||||
|
||||
/**
|
||||
* Once you have initialized the \c cvt structure using SDL_BuildAudioCVT(), |
||||
* created an audio buffer \c cvt->buf, and filled it with \c cvt->len bytes of |
||||
* audio data in the source format, this function will convert it in-place |
||||
* to the desired format. |
||||
* |
||||
* The data conversion may expand the size of the audio data, so the buffer |
||||
* \c cvt->buf should be allocated after the \c cvt structure is initialized by |
||||
* SDL_BuildAudioCVT(), and should be \c cvt->len*cvt->len_mult bytes long. |
||||
* |
||||
* \return 0 on success or -1 if \c cvt->buf is NULL. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_ConvertAudio(SDL_AudioCVT * cvt); |
||||
|
||||
/* SDL_AudioStream is a new audio conversion interface.
|
||||
The benefits vs SDL_AudioCVT: |
||||
- it can handle resampling data in chunks without generating |
||||
artifacts, when it doesn't have the complete buffer available. |
||||
- it can handle incoming data in any variable size. |
||||
- You push data as you have it, and pull it when you need it |
||||
*/ |
||||
/* this is opaque to the outside world. */ |
||||
struct _SDL_AudioStream; |
||||
typedef struct _SDL_AudioStream SDL_AudioStream; |
||||
|
||||
/**
|
||||
* Create a new audio stream |
||||
* |
||||
* \param src_format The format of the source audio |
||||
* \param src_channels The number of channels of the source audio |
||||
* \param src_rate The sampling rate of the source audio |
||||
* \param dst_format The format of the desired audio output |
||||
* \param dst_channels The number of channels of the desired audio output |
||||
* \param dst_rate The sampling rate of the desired audio output |
||||
* \return 0 on success, or -1 on error. |
||||
* |
||||
* \sa SDL_AudioStreamPut |
||||
* \sa SDL_AudioStreamGet |
||||
* \sa SDL_AudioStreamAvailable |
||||
* \sa SDL_AudioStreamFlush |
||||
* \sa SDL_AudioStreamClear |
||||
* \sa SDL_FreeAudioStream |
||||
*/ |
||||
extern DECLSPEC SDL_AudioStream * SDLCALL SDL_NewAudioStream(const SDL_AudioFormat src_format, |
||||
const Uint8 src_channels, |
||||
const int src_rate, |
||||
const SDL_AudioFormat dst_format, |
||||
const Uint8 dst_channels, |
||||
const int dst_rate); |
||||
|
||||
/**
|
||||
* Add data to be converted/resampled to the stream |
||||
* |
||||
* \param stream The stream the audio data is being added to |
||||
* \param buf A pointer to the audio data to add |
||||
* \param len The number of bytes to write to the stream |
||||
* \return 0 on success, or -1 on error. |
||||
* |
||||
* \sa SDL_NewAudioStream |
||||
* \sa SDL_AudioStreamGet |
||||
* \sa SDL_AudioStreamAvailable |
||||
* \sa SDL_AudioStreamFlush |
||||
* \sa SDL_AudioStreamClear |
||||
* \sa SDL_FreeAudioStream |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_AudioStreamPut(SDL_AudioStream *stream, const void *buf, int len); |
||||
|
||||
/**
|
||||
* Get converted/resampled data from the stream |
||||
* |
||||
* \param stream The stream the audio is being requested from |
||||
* \param buf A buffer to fill with audio data |
||||
* \param len The maximum number of bytes to fill |
||||
* \return The number of bytes read from the stream, or -1 on error |
||||
* |
||||
* \sa SDL_NewAudioStream |
||||
* \sa SDL_AudioStreamPut |
||||
* \sa SDL_AudioStreamAvailable |
||||
* \sa SDL_AudioStreamFlush |
||||
* \sa SDL_AudioStreamClear |
||||
* \sa SDL_FreeAudioStream |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_AudioStreamGet(SDL_AudioStream *stream, void *buf, int len); |
||||
|
||||
/**
|
||||
* Get the number of converted/resampled bytes available. The stream may be |
||||
* buffering data behind the scenes until it has enough to resample |
||||
* correctly, so this number might be lower than what you expect, or even |
||||
* be zero. Add more data or flush the stream if you need the data now. |
||||
* |
||||
* \sa SDL_NewAudioStream |
||||
* \sa SDL_AudioStreamPut |
||||
* \sa SDL_AudioStreamGet |
||||
* \sa SDL_AudioStreamFlush |
||||
* \sa SDL_AudioStreamClear |
||||
* \sa SDL_FreeAudioStream |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_AudioStreamAvailable(SDL_AudioStream *stream); |
||||
|
||||
/**
|
||||
* Tell the stream that you're done sending data, and anything being buffered |
||||
* should be converted/resampled and made available immediately. |
||||
* |
||||
* It is legal to add more data to a stream after flushing, but there will |
||||
* be audio gaps in the output. Generally this is intended to signal the |
||||
* end of input, so the complete output becomes available. |
||||
* |
||||
* \sa SDL_NewAudioStream |
||||
* \sa SDL_AudioStreamPut |
||||
* \sa SDL_AudioStreamGet |
||||
* \sa SDL_AudioStreamAvailable |
||||
* \sa SDL_AudioStreamClear |
||||
* \sa SDL_FreeAudioStream |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_AudioStreamFlush(SDL_AudioStream *stream); |
||||
|
||||
/**
|
||||
* Clear any pending data in the stream without converting it |
||||
* |
||||
* \sa SDL_NewAudioStream |
||||
* \sa SDL_AudioStreamPut |
||||
* \sa SDL_AudioStreamGet |
||||
* \sa SDL_AudioStreamAvailable |
||||
* \sa SDL_AudioStreamFlush |
||||
* \sa SDL_FreeAudioStream |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_AudioStreamClear(SDL_AudioStream *stream); |
||||
|
||||
/**
|
||||
* Free an audio stream |
||||
* |
||||
* \sa SDL_NewAudioStream |
||||
* \sa SDL_AudioStreamPut |
||||
* \sa SDL_AudioStreamGet |
||||
* \sa SDL_AudioStreamAvailable |
||||
* \sa SDL_AudioStreamFlush |
||||
* \sa SDL_AudioStreamClear |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_FreeAudioStream(SDL_AudioStream *stream); |
||||
|
||||
#define SDL_MIX_MAXVOLUME 128 |
||||
/**
|
||||
* This takes two audio buffers of the playing audio format and mixes |
||||
* them, performing addition, volume adjustment, and overflow clipping. |
||||
* The volume ranges from 0 - 128, and should be set to ::SDL_MIX_MAXVOLUME |
||||
* for full audio volume. Note this does not change hardware volume. |
||||
* This is provided for convenience -- you can mix your own audio data. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_MixAudio(Uint8 * dst, const Uint8 * src, |
||||
Uint32 len, int volume); |
||||
|
||||
/**
|
||||
* This works like SDL_MixAudio(), but you specify the audio format instead of |
||||
* using the format of audio device 1. Thus it can be used when no audio |
||||
* device is open at all. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_MixAudioFormat(Uint8 * dst, |
||||
const Uint8 * src, |
||||
SDL_AudioFormat format, |
||||
Uint32 len, int volume); |
||||
|
||||
/**
|
||||
* Queue more audio on non-callback devices. |
||||
* |
||||
* (If you are looking to retrieve queued audio from a non-callback capture |
||||
* device, you want SDL_DequeueAudio() instead. This will return -1 to |
||||
* signify an error if you use it with capture devices.) |
||||
* |
||||
* SDL offers two ways to feed audio to the device: you can either supply a |
||||
* callback that SDL triggers with some frequency to obtain more audio |
||||
* (pull method), or you can supply no callback, and then SDL will expect |
||||
* you to supply data at regular intervals (push method) with this function. |
||||
* |
||||
* There are no limits on the amount of data you can queue, short of |
||||
* exhaustion of address space. Queued data will drain to the device as |
||||
* necessary without further intervention from you. If the device needs |
||||
* audio but there is not enough queued, it will play silence to make up |
||||
* the difference. This means you will have skips in your audio playback |
||||
* if you aren't routinely queueing sufficient data. |
||||
* |
||||
* This function copies the supplied data, so you are safe to free it when |
||||
* the function returns. This function is thread-safe, but queueing to the |
||||
* same device from two threads at once does not promise which buffer will |
||||
* be queued first. |
||||
* |
||||
* You may not queue audio on a device that is using an application-supplied |
||||
* callback; doing so returns an error. You have to use the audio callback |
||||
* or queue audio with this function, but not both. |
||||
* |
||||
* You should not call SDL_LockAudio() on the device before queueing; SDL |
||||
* handles locking internally for this function. |
||||
* |
||||
* \param dev The device ID to which we will queue audio. |
||||
* \param data The data to queue to the device for later playback. |
||||
* \param len The number of bytes (not samples!) to which (data) points. |
||||
* \return 0 on success, or -1 on error. |
||||
* |
||||
* \sa SDL_GetQueuedAudioSize |
||||
* \sa SDL_ClearQueuedAudio |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_QueueAudio(SDL_AudioDeviceID dev, const void *data, Uint32 len); |
||||
|
||||
/**
|
||||
* Dequeue more audio on non-callback devices. |
||||
* |
||||
* (If you are looking to queue audio for output on a non-callback playback |
||||
* device, you want SDL_QueueAudio() instead. This will always return 0 |
||||
* if you use it with playback devices.) |
||||
* |
||||
* SDL offers two ways to retrieve audio from a capture device: you can |
||||
* either supply a callback that SDL triggers with some frequency as the |
||||
* device records more audio data, (push method), or you can supply no |
||||
* callback, and then SDL will expect you to retrieve data at regular |
||||
* intervals (pull method) with this function. |
||||
* |
||||
* There are no limits on the amount of data you can queue, short of |
||||
* exhaustion of address space. Data from the device will keep queuing as |
||||
* necessary without further intervention from you. This means you will |
||||
* eventually run out of memory if you aren't routinely dequeueing data. |
||||
* |
||||
* Capture devices will not queue data when paused; if you are expecting |
||||
* to not need captured audio for some length of time, use |
||||
* SDL_PauseAudioDevice() to stop the capture device from queueing more |
||||
* data. This can be useful during, say, level loading times. When |
||||
* unpaused, capture devices will start queueing data from that point, |
||||
* having flushed any capturable data available while paused. |
||||
* |
||||
* This function is thread-safe, but dequeueing from the same device from |
||||
* two threads at once does not promise which thread will dequeued data |
||||
* first. |
||||
* |
||||
* You may not dequeue audio from a device that is using an |
||||
* application-supplied callback; doing so returns an error. You have to use |
||||
* the audio callback, or dequeue audio with this function, but not both. |
||||
* |
||||
* You should not call SDL_LockAudio() on the device before queueing; SDL |
||||
* handles locking internally for this function. |
||||
* |
||||
* \param dev The device ID from which we will dequeue audio. |
||||
* \param data A pointer into where audio data should be copied. |
||||
* \param len The number of bytes (not samples!) to which (data) points. |
||||
* \return number of bytes dequeued, which could be less than requested. |
||||
* |
||||
* \sa SDL_GetQueuedAudioSize |
||||
* \sa SDL_ClearQueuedAudio |
||||
*/ |
||||
extern DECLSPEC Uint32 SDLCALL SDL_DequeueAudio(SDL_AudioDeviceID dev, void *data, Uint32 len); |
||||
|
||||
/**
|
||||
* Get the number of bytes of still-queued audio. |
||||
* |
||||
* For playback device: |
||||
* |
||||
* This is the number of bytes that have been queued for playback with |
||||
* SDL_QueueAudio(), but have not yet been sent to the hardware. This |
||||
* number may shrink at any time, so this only informs of pending data. |
||||
* |
||||
* Once we've sent it to the hardware, this function can not decide the |
||||
* exact byte boundary of what has been played. It's possible that we just |
||||
* gave the hardware several kilobytes right before you called this |
||||
* function, but it hasn't played any of it yet, or maybe half of it, etc. |
||||
* |
||||
* For capture devices: |
||||
* |
||||
* This is the number of bytes that have been captured by the device and |
||||
* are waiting for you to dequeue. This number may grow at any time, so |
||||
* this only informs of the lower-bound of available data. |
||||
* |
||||
* You may not queue audio on a device that is using an application-supplied |
||||
* callback; calling this function on such a device always returns 0. |
||||
* You have to queue audio with SDL_QueueAudio()/SDL_DequeueAudio(), or use |
||||
* the audio callback, but not both. |
||||
* |
||||
* You should not call SDL_LockAudio() on the device before querying; SDL |
||||
* handles locking internally for this function. |
||||
* |
||||
* \param dev The device ID of which we will query queued audio size. |
||||
* \return Number of bytes (not samples!) of queued audio. |
||||
* |
||||
* \sa SDL_QueueAudio |
||||
* \sa SDL_ClearQueuedAudio |
||||
*/ |
||||
extern DECLSPEC Uint32 SDLCALL SDL_GetQueuedAudioSize(SDL_AudioDeviceID dev); |
||||
|
||||
/**
|
||||
* Drop any queued audio data. For playback devices, this is any queued data |
||||
* still waiting to be submitted to the hardware. For capture devices, this |
||||
* is any data that was queued by the device that hasn't yet been dequeued by |
||||
* the application. |
||||
* |
||||
* Immediately after this call, SDL_GetQueuedAudioSize() will return 0. For |
||||
* playback devices, the hardware will start playing silence if more audio |
||||
* isn't queued. Unpaused capture devices will start filling the queue again |
||||
* as soon as they have more data available (which, depending on the state |
||||
* of the hardware and the thread, could be before this function call |
||||
* returns!). |
||||
* |
||||
* This will not prevent playback of queued audio that's already been sent |
||||
* to the hardware, as we can not undo that, so expect there to be some |
||||
* fraction of a second of audio that might still be heard. This can be |
||||
* useful if you want to, say, drop any pending music during a level change |
||||
* in your game. |
||||
* |
||||
* You may not queue audio on a device that is using an application-supplied |
||||
* callback; calling this function on such a device is always a no-op. |
||||
* You have to queue audio with SDL_QueueAudio()/SDL_DequeueAudio(), or use |
||||
* the audio callback, but not both. |
||||
* |
||||
* You should not call SDL_LockAudio() on the device before clearing the |
||||
* queue; SDL handles locking internally for this function. |
||||
* |
||||
* This function always succeeds and thus returns void. |
||||
* |
||||
* \param dev The device ID of which to clear the audio queue. |
||||
* |
||||
* \sa SDL_QueueAudio |
||||
* \sa SDL_GetQueuedAudioSize |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_ClearQueuedAudio(SDL_AudioDeviceID dev); |
||||
|
||||
|
||||
/**
|
||||
* \name Audio lock functions |
||||
* |
||||
* The lock manipulated by these functions protects the callback function. |
||||
* During a SDL_LockAudio()/SDL_UnlockAudio() pair, you can be guaranteed that |
||||
* the callback function is not running. Do not call these from the callback |
||||
* function or you will cause deadlock. |
||||
*/ |
||||
/* @{ */ |
||||
extern DECLSPEC void SDLCALL SDL_LockAudio(void); |
||||
extern DECLSPEC void SDLCALL SDL_LockAudioDevice(SDL_AudioDeviceID dev); |
||||
extern DECLSPEC void SDLCALL SDL_UnlockAudio(void); |
||||
extern DECLSPEC void SDLCALL SDL_UnlockAudioDevice(SDL_AudioDeviceID dev); |
||||
/* @} *//* Audio lock functions */ |
||||
|
||||
/**
|
||||
* This function shuts down audio processing and closes the audio device. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_CloseAudio(void); |
||||
extern DECLSPEC void SDLCALL SDL_CloseAudioDevice(SDL_AudioDeviceID dev); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_audio_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,121 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_bits.h |
||||
* |
||||
* Functions for fiddling with bits and bitmasks. |
||||
*/ |
||||
|
||||
#ifndef SDL_bits_h_ |
||||
#define SDL_bits_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \file SDL_bits.h |
||||
*/ |
||||
|
||||
/**
|
||||
* Get the index of the most significant bit. Result is undefined when called |
||||
* with 0. This operation can also be stated as "count leading zeroes" and |
||||
* "log base 2". |
||||
* |
||||
* \return Index of the most significant bit, or -1 if the value is 0. |
||||
*/ |
||||
#if defined(__WATCOMC__) && defined(__386__) |
||||
extern _inline int _SDL_clz_watcom (Uint32); |
||||
#pragma aux _SDL_clz_watcom = \ |
||||
"bsr eax, eax" \
|
||||
"xor eax, 31" \
|
||||
parm [eax] nomemory \
|
||||
value [eax] \
|
||||
modify exact [eax] nomemory; |
||||
#endif |
||||
|
||||
SDL_FORCE_INLINE int |
||||
SDL_MostSignificantBitIndex32(Uint32 x) |
||||
{ |
||||
#if defined(__GNUC__) && (__GNUC__ >= 4 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) |
||||
/* Count Leading Zeroes builtin in GCC.
|
||||
* http://gcc.gnu.org/onlinedocs/gcc-4.3.4/gcc/Other-Builtins.html
|
||||
*/ |
||||
if (x == 0) { |
||||
return -1; |
||||
} |
||||
return 31 - __builtin_clz(x); |
||||
#elif defined(__WATCOMC__) && defined(__386__) |
||||
if (x == 0) { |
||||
return -1; |
||||
} |
||||
return 31 - _SDL_clz_watcom(x); |
||||
#else |
||||
/* Based off of Bit Twiddling Hacks by Sean Eron Anderson
|
||||
* <seander@cs.stanford.edu>, released in the public domain. |
||||
* http://graphics.stanford.edu/~seander/bithacks.html#IntegerLog
|
||||
*/ |
||||
const Uint32 b[] = {0x2, 0xC, 0xF0, 0xFF00, 0xFFFF0000}; |
||||
const int S[] = {1, 2, 4, 8, 16}; |
||||
|
||||
int msbIndex = 0; |
||||
int i; |
||||
|
||||
if (x == 0) { |
||||
return -1; |
||||
} |
||||
|
||||
for (i = 4; i >= 0; i--) |
||||
{ |
||||
if (x & b[i]) |
||||
{ |
||||
x >>= S[i]; |
||||
msbIndex |= S[i]; |
||||
} |
||||
} |
||||
|
||||
return msbIndex; |
||||
#endif |
||||
} |
||||
|
||||
SDL_FORCE_INLINE SDL_bool |
||||
SDL_HasExactlyOneBitSet32(Uint32 x) |
||||
{ |
||||
if (x && !(x & (x - 1))) { |
||||
return SDL_TRUE; |
||||
} |
||||
return SDL_FALSE; |
||||
} |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_bits_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,120 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_blendmode.h |
||||
* |
||||
* Header file declaring the SDL_BlendMode enumeration |
||||
*/ |
||||
|
||||
#ifndef SDL_blendmode_h_ |
||||
#define SDL_blendmode_h_ |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief The blend mode used in SDL_RenderCopy() and drawing operations. |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_BLENDMODE_NONE = 0x00000000, /**< no blending
|
||||
dstRGBA = srcRGBA */ |
||||
SDL_BLENDMODE_BLEND = 0x00000001, /**< alpha blending
|
||||
dstRGB = (srcRGB * srcA) + (dstRGB * (1-srcA)) |
||||
dstA = srcA + (dstA * (1-srcA)) */ |
||||
SDL_BLENDMODE_ADD = 0x00000002, /**< additive blending
|
||||
dstRGB = (srcRGB * srcA) + dstRGB |
||||
dstA = dstA */ |
||||
SDL_BLENDMODE_MOD = 0x00000004, /**< color modulate
|
||||
dstRGB = srcRGB * dstRGB |
||||
dstA = dstA */ |
||||
SDL_BLENDMODE_INVALID = 0x7FFFFFFF |
||||
|
||||
/* Additional custom blend modes can be returned by SDL_ComposeCustomBlendMode() */ |
||||
|
||||
} SDL_BlendMode; |
||||
|
||||
/**
|
||||
* \brief The blend operation used when combining source and destination pixel components |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_BLENDOPERATION_ADD = 0x1, /**< dst + src: supported by all renderers */ |
||||
SDL_BLENDOPERATION_SUBTRACT = 0x2, /**< dst - src : supported by D3D9, D3D11, OpenGL, OpenGLES */ |
||||
SDL_BLENDOPERATION_REV_SUBTRACT = 0x3, /**< src - dst : supported by D3D9, D3D11, OpenGL, OpenGLES */ |
||||
SDL_BLENDOPERATION_MINIMUM = 0x4, /**< min(dst, src) : supported by D3D11 */ |
||||
SDL_BLENDOPERATION_MAXIMUM = 0x5 /**< max(dst, src) : supported by D3D11 */ |
||||
|
||||
} SDL_BlendOperation; |
||||
|
||||
/**
|
||||
* \brief The normalized factor used to multiply pixel components |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_BLENDFACTOR_ZERO = 0x1, /**< 0, 0, 0, 0 */ |
||||
SDL_BLENDFACTOR_ONE = 0x2, /**< 1, 1, 1, 1 */ |
||||
SDL_BLENDFACTOR_SRC_COLOR = 0x3, /**< srcR, srcG, srcB, srcA */ |
||||
SDL_BLENDFACTOR_ONE_MINUS_SRC_COLOR = 0x4, /**< 1-srcR, 1-srcG, 1-srcB, 1-srcA */ |
||||
SDL_BLENDFACTOR_SRC_ALPHA = 0x5, /**< srcA, srcA, srcA, srcA */ |
||||
SDL_BLENDFACTOR_ONE_MINUS_SRC_ALPHA = 0x6, /**< 1-srcA, 1-srcA, 1-srcA, 1-srcA */ |
||||
SDL_BLENDFACTOR_DST_COLOR = 0x7, /**< dstR, dstG, dstB, dstA */ |
||||
SDL_BLENDFACTOR_ONE_MINUS_DST_COLOR = 0x8, /**< 1-dstR, 1-dstG, 1-dstB, 1-dstA */ |
||||
SDL_BLENDFACTOR_DST_ALPHA = 0x9, /**< dstA, dstA, dstA, dstA */ |
||||
SDL_BLENDFACTOR_ONE_MINUS_DST_ALPHA = 0xA /**< 1-dstA, 1-dstA, 1-dstA, 1-dstA */ |
||||
|
||||
} SDL_BlendFactor; |
||||
|
||||
/**
|
||||
* \brief Create a custom blend mode, which may or may not be supported by a given renderer |
||||
* |
||||
* \param srcColorFactor source color factor |
||||
* \param dstColorFactor destination color factor |
||||
* \param colorOperation color operation |
||||
* \param srcAlphaFactor source alpha factor |
||||
* \param dstAlphaFactor destination alpha factor |
||||
* \param alphaOperation alpha operation |
||||
* |
||||
* The result of the blend mode operation will be: |
||||
* dstRGB = dstRGB * dstColorFactor colorOperation srcRGB * srcColorFactor |
||||
* and |
||||
* dstA = dstA * dstAlphaFactor alphaOperation srcA * srcAlphaFactor |
||||
*/ |
||||
extern DECLSPEC SDL_BlendMode SDLCALL SDL_ComposeCustomBlendMode(SDL_BlendFactor srcColorFactor, |
||||
SDL_BlendFactor dstColorFactor, |
||||
SDL_BlendOperation colorOperation, |
||||
SDL_BlendFactor srcAlphaFactor, |
||||
SDL_BlendFactor dstAlphaFactor, |
||||
SDL_BlendOperation alphaOperation); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_blendmode_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,71 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_clipboard.h |
||||
* |
||||
* Include file for SDL clipboard handling |
||||
*/ |
||||
|
||||
#ifndef SDL_clipboard_h_ |
||||
#define SDL_clipboard_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* Function prototypes */ |
||||
|
||||
/**
|
||||
* \brief Put UTF-8 text into the clipboard |
||||
* |
||||
* \sa SDL_GetClipboardText() |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SetClipboardText(const char *text); |
||||
|
||||
/**
|
||||
* \brief Get UTF-8 text from the clipboard, which must be freed with SDL_free() |
||||
* |
||||
* \sa SDL_SetClipboardText() |
||||
*/ |
||||
extern DECLSPEC char * SDLCALL SDL_GetClipboardText(void); |
||||
|
||||
/**
|
||||
* \brief Returns a flag indicating whether the clipboard exists and contains a text string that is non-empty |
||||
* |
||||
* \sa SDL_GetClipboardText() |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasClipboardText(void); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_clipboard_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,419 @@ |
||||
/* include/SDL_config.h. Generated from SDL_config.h.in by configure. */ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
#ifndef SDL_config_h_ |
||||
#define SDL_config_h_ |
||||
|
||||
/**
|
||||
* \file SDL_config.h.in |
||||
* |
||||
* This is a set of defines to configure the SDL features |
||||
*/ |
||||
|
||||
/* General platform specific identifiers */ |
||||
#include "SDL_platform.h" |
||||
|
||||
/* Make sure that this isn't included by Visual C++ */ |
||||
#ifdef _MSC_VER |
||||
#error You should run hg revert SDL_config.h |
||||
#endif |
||||
|
||||
/* C language features */ |
||||
/* #undef const */ |
||||
/* #undef inline */ |
||||
/* #undef volatile */ |
||||
|
||||
/* C datatypes */ |
||||
#ifdef __LP64__ |
||||
#define SIZEOF_VOIDP 8 |
||||
#else |
||||
#define SIZEOF_VOIDP 4 |
||||
#endif |
||||
#define HAVE_GCC_ATOMICS 1 |
||||
/* #undef HAVE_GCC_SYNC_LOCK_TEST_AND_SET */ |
||||
|
||||
/* Comment this if you want to build without any C library requirements */ |
||||
#define HAVE_LIBC 1 |
||||
#if HAVE_LIBC |
||||
|
||||
/* Useful headers */ |
||||
#define STDC_HEADERS 1 |
||||
#define HAVE_ALLOCA_H 1 |
||||
#define HAVE_CTYPE_H 1 |
||||
#define HAVE_FLOAT_H 1 |
||||
#define HAVE_ICONV_H 1 |
||||
#define HAVE_INTTYPES_H 1 |
||||
#define HAVE_LIMITS_H 1 |
||||
/* #undef HAVE_MALLOC_H */ |
||||
#define HAVE_MATH_H 1 |
||||
#define HAVE_MEMORY_H 1 |
||||
#define HAVE_SIGNAL_H 1 |
||||
#define HAVE_STDARG_H 1 |
||||
#define HAVE_STDINT_H 1 |
||||
#define HAVE_STDIO_H 1 |
||||
#define HAVE_STDLIB_H 1 |
||||
#define HAVE_STRINGS_H 1 |
||||
#define HAVE_STRING_H 1 |
||||
#define HAVE_SYS_TYPES_H 1 |
||||
#define HAVE_WCHAR_H 1 |
||||
/* #undef HAVE_PTHREAD_NP_H */ |
||||
#define HAVE_LIBUNWIND_H 1 |
||||
|
||||
/* C library functions */ |
||||
#define HAVE_MALLOC 1 |
||||
#define HAVE_CALLOC 1 |
||||
#define HAVE_REALLOC 1 |
||||
#define HAVE_FREE 1 |
||||
#define HAVE_ALLOCA 1 |
||||
#ifndef __WIN32__ /* Don't use C runtime versions of these on Windows */ |
||||
#define HAVE_GETENV 1 |
||||
#define HAVE_SETENV 1 |
||||
#define HAVE_PUTENV 1 |
||||
#define HAVE_UNSETENV 1 |
||||
#endif |
||||
#define HAVE_QSORT 1 |
||||
#define HAVE_ABS 1 |
||||
#define HAVE_BCOPY 1 |
||||
#define HAVE_MEMSET 1 |
||||
#define HAVE_MEMCPY 1 |
||||
#define HAVE_MEMMOVE 1 |
||||
#define HAVE_MEMCMP 1 |
||||
#define HAVE_WCSLEN 1 |
||||
/* #undef HAVE_WCSLCPY */ |
||||
/* #undef HAVE_WCSLCAT */ |
||||
#define HAVE_WCSCMP 1 |
||||
#define HAVE_STRLEN 1 |
||||
#define HAVE_STRLCPY 1 |
||||
#define HAVE_STRLCAT 1 |
||||
/* #undef HAVE__STRREV */ |
||||
/* #undef HAVE__STRUPR */ |
||||
/* #undef HAVE__STRLWR */ |
||||
/* #undef HAVE_INDEX */ |
||||
/* #undef HAVE_RINDEX */ |
||||
#define HAVE_STRCHR 1 |
||||
#define HAVE_STRRCHR 1 |
||||
#define HAVE_STRSTR 1 |
||||
/* #undef HAVE_ITOA */ |
||||
/* #undef HAVE__LTOA */ |
||||
/* #undef HAVE__UITOA */ |
||||
/* #undef HAVE__ULTOA */ |
||||
#define HAVE_STRTOL 1 |
||||
#define HAVE_STRTOUL 1 |
||||
/* #undef HAVE__I64TOA */ |
||||
/* #undef HAVE__UI64TOA */ |
||||
#define HAVE_STRTOLL 1 |
||||
#define HAVE_STRTOULL 1 |
||||
#define HAVE_STRTOD 1 |
||||
#define HAVE_ATOI 1 |
||||
#define HAVE_ATOF 1 |
||||
#define HAVE_STRCMP 1 |
||||
#define HAVE_STRNCMP 1 |
||||
/* #undef HAVE__STRICMP */ |
||||
#define HAVE_STRCASECMP 1 |
||||
/* #undef HAVE__STRNICMP */ |
||||
#define HAVE_STRNCASECMP 1 |
||||
/* #undef HAVE_SSCANF */ |
||||
#define HAVE_VSSCANF 1 |
||||
/* #undef HAVE_SNPRINTF */ |
||||
#define HAVE_VSNPRINTF 1 |
||||
#define HAVE_M_PI /**/ |
||||
#define HAVE_ACOS 1 |
||||
#define HAVE_ACOSF 1 |
||||
#define HAVE_ASIN 1 |
||||
#define HAVE_ASINF 1 |
||||
#define HAVE_ATAN 1 |
||||
#define HAVE_ATANF 1 |
||||
#define HAVE_ATAN2 1 |
||||
#define HAVE_ATAN2F 1 |
||||
#define HAVE_CEIL 1 |
||||
#define HAVE_CEILF 1 |
||||
#define HAVE_COPYSIGN 1 |
||||
#define HAVE_COPYSIGNF 1 |
||||
#define HAVE_COS 1 |
||||
#define HAVE_COSF 1 |
||||
#define HAVE_EXP 1 |
||||
#define HAVE_EXPF 1 |
||||
#define HAVE_FABS 1 |
||||
#define HAVE_FABSF 1 |
||||
#define HAVE_FLOOR 1 |
||||
#define HAVE_FLOORF 1 |
||||
#define HAVE_FMOD 1 |
||||
#define HAVE_FMODF 1 |
||||
#define HAVE_LOG 1 |
||||
#define HAVE_LOGF 1 |
||||
#define HAVE_LOG10 1 |
||||
#define HAVE_LOG10F 1 |
||||
#define HAVE_POW 1 |
||||
#define HAVE_POWF 1 |
||||
#define HAVE_SCALBN 1 |
||||
#define HAVE_SCALBNF 1 |
||||
#define HAVE_SIN 1 |
||||
#define HAVE_SINF 1 |
||||
#define HAVE_SQRT 1 |
||||
#define HAVE_SQRTF 1 |
||||
#define HAVE_TAN 1 |
||||
#define HAVE_TANF 1 |
||||
/* #undef HAVE_FOPEN64 */ |
||||
#define HAVE_FSEEKO 1 |
||||
/* #undef HAVE_FSEEKO64 */ |
||||
#define HAVE_SIGACTION 1 |
||||
#define HAVE_SA_SIGACTION 1 |
||||
#define HAVE_SETJMP 1 |
||||
#define HAVE_NANOSLEEP 1 |
||||
#define HAVE_SYSCONF 1 |
||||
#define HAVE_SYSCTLBYNAME 1 |
||||
/* #undef HAVE_CLOCK_GETTIME */ |
||||
/* #undef HAVE_GETPAGESIZE */ |
||||
#define HAVE_MPROTECT 1 |
||||
#define HAVE_ICONV 1 |
||||
#define HAVE_PTHREAD_SETNAME_NP 1 |
||||
/* #undef HAVE_PTHREAD_SET_NAME_NP */ |
||||
/* #undef HAVE_SEM_TIMEDWAIT */ |
||||
/* #undef HAVE_GETAUXVAL */ |
||||
#define HAVE_POLL 1 |
||||
#define HAVE__EXIT 1 |
||||
|
||||
#else |
||||
#define HAVE_STDARG_H 1 |
||||
#define HAVE_STDDEF_H 1 |
||||
#define HAVE_STDINT_H 1 |
||||
#endif /* HAVE_LIBC */ |
||||
|
||||
/* #undef HAVE_ALTIVEC_H */ |
||||
/* #undef HAVE_DBUS_DBUS_H */ |
||||
/* #undef HAVE_FCITX_FRONTEND_H */ |
||||
/* #undef HAVE_IBUS_IBUS_H */ |
||||
#define HAVE_IMMINTRIN_H 1 |
||||
/* #undef HAVE_LIBSAMPLERATE_H */ |
||||
/* #undef HAVE_LIBUDEV_H */ |
||||
|
||||
/* #undef HAVE_DDRAW_H */ |
||||
/* #undef HAVE_DINPUT_H */ |
||||
/* #undef HAVE_DSOUND_H */ |
||||
/* #undef HAVE_DXGI_H */ |
||||
/* #undef HAVE_XINPUT_H */ |
||||
/* #undef HAVE_ENDPOINTVOLUME_H */ |
||||
/* #undef HAVE_MMDEVICEAPI_H */ |
||||
/* #undef HAVE_AUDIOCLIENT_H */ |
||||
/* #undef HAVE_XINPUT_GAMEPAD_EX */ |
||||
/* #undef HAVE_XINPUT_STATE_EX */ |
||||
|
||||
/* SDL internal assertion support */ |
||||
/* #undef SDL_DEFAULT_ASSERT_LEVEL */ |
||||
|
||||
/* Allow disabling of core subsystems */ |
||||
/* #undef SDL_ATOMIC_DISABLED */ |
||||
/* #undef SDL_AUDIO_DISABLED */ |
||||
/* #undef SDL_CPUINFO_DISABLED */ |
||||
/* #undef SDL_EVENTS_DISABLED */ |
||||
/* #undef SDL_FILE_DISABLED */ |
||||
/* #undef SDL_JOYSTICK_DISABLED */ |
||||
/* #undef SDL_HAPTIC_DISABLED */ |
||||
/* #undef SDL_SENSOR_DISABLED */ |
||||
/* #undef SDL_LOADSO_DISABLED */ |
||||
/* #undef SDL_RENDER_DISABLED */ |
||||
/* #undef SDL_THREADS_DISABLED */ |
||||
/* #undef SDL_TIMERS_DISABLED */ |
||||
/* #undef SDL_VIDEO_DISABLED */ |
||||
/* #undef SDL_POWER_DISABLED */ |
||||
/* #undef SDL_FILESYSTEM_DISABLED */ |
||||
|
||||
/* Enable various audio drivers */ |
||||
/* #undef SDL_AUDIO_DRIVER_ALSA */ |
||||
/* #undef SDL_AUDIO_DRIVER_ALSA_DYNAMIC */ |
||||
/* #undef SDL_AUDIO_DRIVER_ANDROID */ |
||||
/* #undef SDL_AUDIO_DRIVER_ARTS */ |
||||
/* #undef SDL_AUDIO_DRIVER_ARTS_DYNAMIC */ |
||||
#define SDL_AUDIO_DRIVER_COREAUDIO 1 |
||||
#define SDL_AUDIO_DRIVER_DISK 1 |
||||
/* #undef SDL_AUDIO_DRIVER_DSOUND */ |
||||
#define SDL_AUDIO_DRIVER_DUMMY 1 |
||||
/* #undef SDL_AUDIO_DRIVER_EMSCRIPTEN */ |
||||
/* #undef SDL_AUDIO_DRIVER_ESD */ |
||||
/* #undef SDL_AUDIO_DRIVER_ESD_DYNAMIC */ |
||||
/* #undef SDL_AUDIO_DRIVER_FUSIONSOUND */ |
||||
/* #undef SDL_AUDIO_DRIVER_FUSIONSOUND_DYNAMIC */ |
||||
/* #undef SDL_AUDIO_DRIVER_HAIKU */ |
||||
/* #undef SDL_AUDIO_DRIVER_JACK */ |
||||
/* #undef SDL_AUDIO_DRIVER_JACK_DYNAMIC */ |
||||
/* #undef SDL_AUDIO_DRIVER_NACL */ |
||||
/* #undef SDL_AUDIO_DRIVER_NAS */ |
||||
/* #undef SDL_AUDIO_DRIVER_NAS_DYNAMIC */ |
||||
/* #undef SDL_AUDIO_DRIVER_NETBSD */ |
||||
/* #undef SDL_AUDIO_DRIVER_OSS */ |
||||
/* #undef SDL_AUDIO_DRIVER_OSS_SOUNDCARD_H */ |
||||
/* #undef SDL_AUDIO_DRIVER_PAUDIO */ |
||||
/* #undef SDL_AUDIO_DRIVER_PULSEAUDIO */ |
||||
/* #undef SDL_AUDIO_DRIVER_PULSEAUDIO_DYNAMIC */ |
||||
/* #undef SDL_AUDIO_DRIVER_QSA */ |
||||
/* #undef SDL_AUDIO_DRIVER_SNDIO */ |
||||
/* #undef SDL_AUDIO_DRIVER_SNDIO_DYNAMIC */ |
||||
/* #undef SDL_AUDIO_DRIVER_SUNAUDIO */ |
||||
/* #undef SDL_AUDIO_DRIVER_WASAPI */ |
||||
/* #undef SDL_AUDIO_DRIVER_WINMM */ |
||||
|
||||
/* Enable various input drivers */ |
||||
/* #undef SDL_INPUT_LINUXEV */ |
||||
/* #undef SDL_INPUT_LINUXKD */ |
||||
/* #undef SDL_INPUT_TSLIB */ |
||||
/* #undef SDL_JOYSTICK_HAIKU */ |
||||
/* #undef SDL_JOYSTICK_DINPUT */ |
||||
/* #undef SDL_JOYSTICK_XINPUT */ |
||||
/* #undef SDL_JOYSTICK_DUMMY */ |
||||
#define SDL_JOYSTICK_IOKIT 1 |
||||
/* #undef SDL_JOYSTICK_LINUX */ |
||||
/* #undef SDL_JOYSTICK_ANDROID */ |
||||
/* #undef SDL_JOYSTICK_WINMM */ |
||||
/* #undef SDL_JOYSTICK_USBHID */ |
||||
/* #undef SDL_JOYSTICK_USBHID_MACHINE_JOYSTICK_H */ |
||||
#define SDL_JOYSTICK_HIDAPI 1 |
||||
/* #undef SDL_JOYSTICK_EMSCRIPTEN */ |
||||
/* #undef SDL_HAPTIC_DUMMY */ |
||||
/* #undef SDL_HAPTIC_ANDROID */ |
||||
/* #undef SDL_HAPTIC_LINUX */ |
||||
#define SDL_HAPTIC_IOKIT 1 |
||||
/* #undef SDL_HAPTIC_DINPUT */ |
||||
/* #undef SDL_HAPTIC_XINPUT */ |
||||
|
||||
/* Enable various sensor drivers */ |
||||
/* #undef SDL_SENSOR_ANDROID */ |
||||
#define SDL_SENSOR_DUMMY 1 |
||||
|
||||
/* Enable various shared object loading systems */ |
||||
#define SDL_LOADSO_DLOPEN 1 |
||||
/* #undef SDL_LOADSO_DUMMY */ |
||||
/* #undef SDL_LOADSO_LDG */ |
||||
/* #undef SDL_LOADSO_WINDOWS */ |
||||
|
||||
/* Enable various threading systems */ |
||||
#define SDL_THREAD_PTHREAD 1 |
||||
#define SDL_THREAD_PTHREAD_RECURSIVE_MUTEX 1 |
||||
/* #undef SDL_THREAD_PTHREAD_RECURSIVE_MUTEX_NP */ |
||||
/* #undef SDL_THREAD_WINDOWS */ |
||||
|
||||
/* Enable various timer systems */ |
||||
/* #undef SDL_TIMER_HAIKU */ |
||||
/* #undef SDL_TIMER_DUMMY */ |
||||
#define SDL_TIMER_UNIX 1 |
||||
/* #undef SDL_TIMER_WINDOWS */ |
||||
|
||||
/* Enable various video drivers */ |
||||
/* #undef SDL_VIDEO_DRIVER_HAIKU */ |
||||
#define SDL_VIDEO_DRIVER_COCOA 1 |
||||
/* #undef SDL_VIDEO_DRIVER_DIRECTFB */ |
||||
/* #undef SDL_VIDEO_DRIVER_DIRECTFB_DYNAMIC */ |
||||
#define SDL_VIDEO_DRIVER_DUMMY 1 |
||||
/* #undef SDL_VIDEO_DRIVER_WINDOWS */ |
||||
/* #undef SDL_VIDEO_DRIVER_WAYLAND */ |
||||
/* #undef SDL_VIDEO_DRIVER_WAYLAND_QT_TOUCH */ |
||||
/* #undef SDL_VIDEO_DRIVER_WAYLAND_DYNAMIC */ |
||||
/* #undef SDL_VIDEO_DRIVER_WAYLAND_DYNAMIC_EGL */ |
||||
/* #undef SDL_VIDEO_DRIVER_WAYLAND_DYNAMIC_CURSOR */ |
||||
/* #undef SDL_VIDEO_DRIVER_WAYLAND_DYNAMIC_XKBCOMMON */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11 */ |
||||
/* #undef SDL_VIDEO_DRIVER_RPI */ |
||||
/* #undef SDL_VIDEO_DRIVER_KMSDRM */ |
||||
/* #undef SDL_VIDEO_DRIVER_KMSDRM_DYNAMIC */ |
||||
/* #undef SDL_VIDEO_DRIVER_KMSDRM_DYNAMIC_GBM */ |
||||
/* #undef SDL_VIDEO_DRIVER_ANDROID */ |
||||
/* #undef SDL_VIDEO_DRIVER_EMSCRIPTEN */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_DYNAMIC */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_DYNAMIC_XEXT */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_DYNAMIC_XCURSOR */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_DYNAMIC_XINERAMA */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_DYNAMIC_XINPUT2 */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_DYNAMIC_XRANDR */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_DYNAMIC_XSS */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_DYNAMIC_XVIDMODE */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_XCURSOR */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_XDBE */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_XINERAMA */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_XINPUT2 */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_XINPUT2_SUPPORTS_MULTITOUCH */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_XRANDR */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_XSCRNSAVER */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_XSHAPE */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_XVIDMODE */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_SUPPORTS_GENERIC_EVENTS */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_CONST_PARAM_XEXTADDDISPLAY */ |
||||
/* #undef SDL_VIDEO_DRIVER_X11_HAS_XKBKEYCODETOKEYSYM */ |
||||
/* #undef SDL_VIDEO_DRIVER_NACL */ |
||||
/* #undef SDL_VIDEO_DRIVER_VIVANTE */ |
||||
/* #undef SDL_VIDEO_DRIVER_VIVANTE_VDK */ |
||||
/* #undef SDL_VIDEO_DRIVER_QNX */ |
||||
|
||||
/* #undef SDL_VIDEO_RENDER_D3D */ |
||||
/* #undef SDL_VIDEO_RENDER_D3D11 */ |
||||
#define SDL_VIDEO_RENDER_OGL 1 |
||||
/* #undef SDL_VIDEO_RENDER_OGL_ES */ |
||||
#define SDL_VIDEO_RENDER_OGL_ES2 1 |
||||
/* #undef SDL_VIDEO_RENDER_DIRECTFB */ |
||||
#define SDL_VIDEO_RENDER_METAL 1 |
||||
|
||||
/* Enable OpenGL support */ |
||||
#define SDL_VIDEO_OPENGL 1 |
||||
/* #undef SDL_VIDEO_OPENGL_ES */ |
||||
#define SDL_VIDEO_OPENGL_ES2 1 |
||||
/* #undef SDL_VIDEO_OPENGL_BGL */ |
||||
#define SDL_VIDEO_OPENGL_CGL 1 |
||||
#define SDL_VIDEO_OPENGL_EGL 1 |
||||
/* #undef SDL_VIDEO_OPENGL_GLX */ |
||||
/* #undef SDL_VIDEO_OPENGL_WGL */ |
||||
/* #undef SDL_VIDEO_OPENGL_OSMESA */ |
||||
/* #undef SDL_VIDEO_OPENGL_OSMESA_DYNAMIC */ |
||||
|
||||
/* Enable Vulkan support */ |
||||
#define SDL_VIDEO_VULKAN 1 |
||||
|
||||
/* Enable system power support */ |
||||
/* #undef SDL_POWER_LINUX */ |
||||
/* #undef SDL_POWER_WINDOWS */ |
||||
#define SDL_POWER_MACOSX 1 |
||||
/* #undef SDL_POWER_HAIKU */ |
||||
/* #undef SDL_POWER_ANDROID */ |
||||
/* #undef SDL_POWER_EMSCRIPTEN */ |
||||
/* #undef SDL_POWER_HARDWIRED */ |
||||
|
||||
/* Enable system filesystem support */ |
||||
/* #undef SDL_FILESYSTEM_HAIKU */ |
||||
#define SDL_FILESYSTEM_COCOA 1 |
||||
/* #undef SDL_FILESYSTEM_DUMMY */ |
||||
/* #undef SDL_FILESYSTEM_UNIX */ |
||||
/* #undef SDL_FILESYSTEM_WINDOWS */ |
||||
/* #undef SDL_FILESYSTEM_NACL */ |
||||
/* #undef SDL_FILESYSTEM_ANDROID */ |
||||
/* #undef SDL_FILESYSTEM_EMSCRIPTEN */ |
||||
|
||||
/* Enable assembly routines */ |
||||
#define SDL_ASSEMBLY_ROUTINES 1 |
||||
/* #undef SDL_ALTIVEC_BLITTERS */ |
||||
|
||||
/* Enable ime support */ |
||||
/* #undef SDL_USE_IME */ |
||||
|
||||
/* Enable dynamic udev support */ |
||||
/* #undef SDL_UDEV_DYNAMIC */ |
||||
|
||||
/* Enable dynamic libsamplerate support */ |
||||
/* #undef SDL_LIBSAMPLERATE_DYNAMIC */ |
||||
|
||||
#endif /* SDL_config_h_ */ |
||||
@ -0,0 +1,270 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_cpuinfo.h |
||||
* |
||||
* CPU feature detection for SDL. |
||||
*/ |
||||
|
||||
#ifndef SDL_cpuinfo_h_ |
||||
#define SDL_cpuinfo_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
|
||||
/* Need to do this here because intrin.h has C++ code in it */ |
||||
/* Visual Studio 2005 has a bug where intrin.h conflicts with winnt.h */ |
||||
#if defined(_MSC_VER) && (_MSC_VER >= 1500) && (defined(_M_IX86) || defined(_M_X64)) |
||||
#ifdef __clang__ |
||||
/* Many of the intrinsics SDL uses are not implemented by clang with Visual Studio */ |
||||
#undef __MMX__ |
||||
#undef __SSE__ |
||||
#undef __SSE2__ |
||||
#else |
||||
#include <intrin.h> |
||||
#ifndef _WIN64 |
||||
#ifndef __MMX__ |
||||
#define __MMX__ |
||||
#endif |
||||
#ifndef __3dNOW__ |
||||
#define __3dNOW__ |
||||
#endif |
||||
#endif |
||||
#ifndef __SSE__ |
||||
#define __SSE__ |
||||
#endif |
||||
#ifndef __SSE2__ |
||||
#define __SSE2__ |
||||
#endif |
||||
#endif /* __clang__ */ |
||||
#elif defined(__MINGW64_VERSION_MAJOR) |
||||
#include <intrin.h> |
||||
#else |
||||
/* altivec.h redefining bool causes a number of problems, see bugs 3993 and 4392, so you need to explicitly define SDL_ENABLE_ALTIVEC_H to have it included. */ |
||||
#if defined(HAVE_ALTIVEC_H) && defined(__ALTIVEC__) && !defined(__APPLE_ALTIVEC__) && defined(SDL_ENABLE_ALTIVEC_H) |
||||
#include <altivec.h> |
||||
#endif |
||||
#if !defined(SDL_DISABLE_ARM_NEON_H) |
||||
# if defined(__ARM_NEON) |
||||
# include <arm_neon.h> |
||||
# elif defined(__WINDOWS__) || defined(__WINRT__) |
||||
/* Visual Studio doesn't define __ARM_ARCH, but _M_ARM (if set, always 7), and _M_ARM64 (if set, always 1). */ |
||||
# if defined(_M_ARM) |
||||
# include <armintr.h> |
||||
# include <arm_neon.h> |
||||
# define __ARM_NEON 1 /* Set __ARM_NEON so that it can be used elsewhere, at compile time */ |
||||
# endif |
||||
# if defined (_M_ARM64) |
||||
# include <armintr.h> |
||||
# include <arm_neon.h> |
||||
# define __ARM_NEON 1 /* Set __ARM_NEON so that it can be used elsewhere, at compile time */ |
||||
# endif |
||||
# endif |
||||
#endif |
||||
#if defined(__3dNOW__) && !defined(SDL_DISABLE_MM3DNOW_H) |
||||
#include <mm3dnow.h> |
||||
#endif |
||||
#if defined(HAVE_IMMINTRIN_H) && !defined(SDL_DISABLE_IMMINTRIN_H) |
||||
#include <immintrin.h> |
||||
#else |
||||
#if defined(__MMX__) && !defined(SDL_DISABLE_MMINTRIN_H) |
||||
#include <mmintrin.h> |
||||
#endif |
||||
#if defined(__SSE__) && !defined(SDL_DISABLE_XMMINTRIN_H) |
||||
#include <xmmintrin.h> |
||||
#endif |
||||
#if defined(__SSE2__) && !defined(SDL_DISABLE_EMMINTRIN_H) |
||||
#include <emmintrin.h> |
||||
#endif |
||||
#if defined(__SSE3__) && !defined(SDL_DISABLE_PMMINTRIN_H) |
||||
#include <pmmintrin.h> |
||||
#endif |
||||
#endif /* HAVE_IMMINTRIN_H */ |
||||
#endif /* compiler version */ |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* This is a guess for the cacheline size used for padding.
|
||||
* Most x86 processors have a 64 byte cache line. |
||||
* The 64-bit PowerPC processors have a 128 byte cache line. |
||||
* We'll use the larger value to be generally safe. |
||||
*/ |
||||
#define SDL_CACHELINE_SIZE 128 |
||||
|
||||
/**
|
||||
* This function returns the number of CPU cores available. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GetCPUCount(void); |
||||
|
||||
/**
|
||||
* This function returns the L1 cache line size of the CPU |
||||
* |
||||
* This is useful for determining multi-threaded structure padding |
||||
* or SIMD prefetch sizes. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GetCPUCacheLineSize(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has the RDTSC instruction. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasRDTSC(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has AltiVec features. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasAltiVec(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has MMX features. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasMMX(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has 3DNow! features. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_Has3DNow(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has SSE features. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasSSE(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has SSE2 features. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasSSE2(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has SSE3 features. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasSSE3(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has SSE4.1 features. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasSSE41(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has SSE4.2 features. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasSSE42(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has AVX features. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasAVX(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has AVX2 features. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasAVX2(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has AVX-512F (foundation) features. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasAVX512F(void); |
||||
|
||||
/**
|
||||
* This function returns true if the CPU has NEON (ARM SIMD) features. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasNEON(void); |
||||
|
||||
/**
|
||||
* This function returns the amount of RAM configured in the system, in MB. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GetSystemRAM(void); |
||||
|
||||
/**
|
||||
* \brief Report the alignment this system needs for SIMD allocations. |
||||
* |
||||
* This will return the minimum number of bytes to which a pointer must be |
||||
* aligned to be compatible with SIMD instructions on the current machine. |
||||
* For example, if the machine supports SSE only, it will return 16, but if |
||||
* it supports AVX-512F, it'll return 64 (etc). This only reports values for |
||||
* instruction sets SDL knows about, so if your SDL build doesn't have |
||||
* SDL_HasAVX512F(), then it might return 16 for the SSE support it sees and |
||||
* not 64 for the AVX-512 instructions that exist but SDL doesn't know about. |
||||
* Plan accordingly. |
||||
*/ |
||||
extern DECLSPEC size_t SDLCALL SDL_SIMDGetAlignment(void); |
||||
|
||||
/**
|
||||
* \brief Allocate memory in a SIMD-friendly way. |
||||
* |
||||
* This will allocate a block of memory that is suitable for use with SIMD |
||||
* instructions. Specifically, it will be properly aligned and padded for |
||||
* the system's supported vector instructions. |
||||
* |
||||
* The memory returned will be padded such that it is safe to read or write |
||||
* an incomplete vector at the end of the memory block. This can be useful |
||||
* so you don't have to drop back to a scalar fallback at the end of your |
||||
* SIMD processing loop to deal with the final elements without overflowing |
||||
* the allocated buffer. |
||||
* |
||||
* You must free this memory with SDL_FreeSIMD(), not free() or SDL_free() |
||||
* or delete[], etc. |
||||
* |
||||
* Note that SDL will only deal with SIMD instruction sets it is aware of; |
||||
* for example, SDL 2.0.8 knows that SSE wants 16-byte vectors |
||||
* (SDL_HasSSE()), and AVX2 wants 32 bytes (SDL_HasAVX2()), but doesn't |
||||
* know that AVX-512 wants 64. To be clear: if you can't decide to use an |
||||
* instruction set with an SDL_Has*() function, don't use that instruction |
||||
* set with memory allocated through here. |
||||
* |
||||
* SDL_AllocSIMD(0) will return a non-NULL pointer, assuming the system isn't |
||||
* out of memory. |
||||
* |
||||
* \param len The length, in bytes, of the block to allocated. The actual |
||||
* allocated block might be larger due to padding, etc. |
||||
* \return Pointer to newly-allocated block, NULL if out of memory. |
||||
* |
||||
* \sa SDL_SIMDAlignment |
||||
* \sa SDL_SIMDFree |
||||
*/ |
||||
extern DECLSPEC void * SDLCALL SDL_SIMDAlloc(const size_t len); |
||||
|
||||
/**
|
||||
* \brief Deallocate memory obtained from SDL_SIMDAlloc |
||||
* |
||||
* It is not valid to use this function on a pointer from anything but |
||||
* SDL_SIMDAlloc(). It can't be used on pointers from malloc, realloc, |
||||
* SDL_malloc, memalign, new[], etc. |
||||
* |
||||
* However, SDL_SIMDFree(NULL) is a legal no-op. |
||||
* |
||||
* \sa SDL_SIMDAlloc |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_SIMDFree(void *ptr); |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_cpuinfo_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,260 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_endian.h |
||||
* |
||||
* Functions for reading and writing endian-specific values |
||||
*/ |
||||
|
||||
#ifndef SDL_endian_h_ |
||||
#define SDL_endian_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
|
||||
/**
|
||||
* \name The two types of endianness |
||||
*/ |
||||
/* @{ */ |
||||
#define SDL_LIL_ENDIAN 1234 |
||||
#define SDL_BIG_ENDIAN 4321 |
||||
/* @} */ |
||||
|
||||
#ifndef SDL_BYTEORDER /* Not defined in SDL_config.h? */ |
||||
#ifdef __linux__ |
||||
#include <endian.h> |
||||
#define SDL_BYTEORDER __BYTE_ORDER |
||||
#else /* __linux__ */ |
||||
#if defined(__hppa__) || \ |
||||
defined(__m68k__) || defined(mc68000) || defined(_M_M68K) || \
|
||||
(defined(__MIPS__) && defined(__MISPEB__)) || \
|
||||
defined(__ppc__) || defined(__POWERPC__) || defined(_M_PPC) || \
|
||||
defined(__sparc__) |
||||
#define SDL_BYTEORDER SDL_BIG_ENDIAN |
||||
#else |
||||
#define SDL_BYTEORDER SDL_LIL_ENDIAN |
||||
#endif |
||||
#endif /* __linux__ */ |
||||
#endif /* !SDL_BYTEORDER */ |
||||
|
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \file SDL_endian.h |
||||
*/ |
||||
#if defined(__GNUC__) && defined(__i386__) && \ |
||||
!(__GNUC__ == 2 && __GNUC_MINOR__ == 95 /* broken gcc version */) |
||||
SDL_FORCE_INLINE Uint16 |
||||
SDL_Swap16(Uint16 x) |
||||
{ |
||||
__asm__("xchgb %b0,%h0": "=q"(x):"0"(x)); |
||||
return x; |
||||
} |
||||
#elif defined(__GNUC__) && defined(__x86_64__) |
||||
SDL_FORCE_INLINE Uint16 |
||||
SDL_Swap16(Uint16 x) |
||||
{ |
||||
__asm__("xchgb %b0,%h0": "=Q"(x):"0"(x)); |
||||
return x; |
||||
} |
||||
#elif defined(__GNUC__) && (defined(__powerpc__) || defined(__ppc__)) |
||||
SDL_FORCE_INLINE Uint16 |
||||
SDL_Swap16(Uint16 x) |
||||
{ |
||||
int result; |
||||
|
||||
__asm__("rlwimi %0,%2,8,16,23": "=&r"(result):"0"(x >> 8), "r"(x)); |
||||
return (Uint16)result; |
||||
} |
||||
#elif defined(__GNUC__) && (defined(__M68000__) || defined(__M68020__)) && !defined(__mcoldfire__) |
||||
SDL_FORCE_INLINE Uint16 |
||||
SDL_Swap16(Uint16 x) |
||||
{ |
||||
__asm__("rorw #8,%0": "=d"(x): "0"(x):"cc"); |
||||
return x; |
||||
} |
||||
#elif defined(__WATCOMC__) && defined(__386__) |
||||
extern _inline Uint16 SDL_Swap16(Uint16); |
||||
#pragma aux SDL_Swap16 = \ |
||||
"xchg al, ah" \
|
||||
parm [ax] \
|
||||
modify [ax]; |
||||
#else |
||||
SDL_FORCE_INLINE Uint16 |
||||
SDL_Swap16(Uint16 x) |
||||
{ |
||||
return SDL_static_cast(Uint16, ((x << 8) | (x >> 8))); |
||||
} |
||||
#endif |
||||
|
||||
#if defined(__GNUC__) && defined(__i386__) |
||||
SDL_FORCE_INLINE Uint32 |
||||
SDL_Swap32(Uint32 x) |
||||
{ |
||||
__asm__("bswap %0": "=r"(x):"0"(x)); |
||||
return x; |
||||
} |
||||
#elif defined(__GNUC__) && defined(__x86_64__) |
||||
SDL_FORCE_INLINE Uint32 |
||||
SDL_Swap32(Uint32 x) |
||||
{ |
||||
__asm__("bswapl %0": "=r"(x):"0"(x)); |
||||
return x; |
||||
} |
||||
#elif defined(__GNUC__) && (defined(__powerpc__) || defined(__ppc__)) |
||||
SDL_FORCE_INLINE Uint32 |
||||
SDL_Swap32(Uint32 x) |
||||
{ |
||||
Uint32 result; |
||||
|
||||
__asm__("rlwimi %0,%2,24,16,23": "=&r"(result):"0"(x >> 24), "r"(x)); |
||||
__asm__("rlwimi %0,%2,8,8,15": "=&r"(result):"0"(result), "r"(x)); |
||||
__asm__("rlwimi %0,%2,24,0,7": "=&r"(result):"0"(result), "r"(x)); |
||||
return result; |
||||
} |
||||
#elif defined(__GNUC__) && (defined(__M68000__) || defined(__M68020__)) && !defined(__mcoldfire__) |
||||
SDL_FORCE_INLINE Uint32 |
||||
SDL_Swap32(Uint32 x) |
||||
{ |
||||
__asm__("rorw #8,%0\n\tswap %0\n\trorw #8,%0": "=d"(x): "0"(x):"cc"); |
||||
return x; |
||||
} |
||||
#elif defined(__WATCOMC__) && defined(__386__) |
||||
extern _inline Uint32 SDL_Swap32(Uint32); |
||||
#ifndef __SW_3 /* 486+ */ |
||||
#pragma aux SDL_Swap32 = \ |
||||
"bswap eax" \
|
||||
parm [eax] \
|
||||
modify [eax]; |
||||
#else /* 386-only */ |
||||
#pragma aux SDL_Swap32 = \ |
||||
"xchg al, ah" \
|
||||
"ror eax, 16" \
|
||||
"xchg al, ah" \
|
||||
parm [eax] \
|
||||
modify [eax]; |
||||
#endif |
||||
#else |
||||
SDL_FORCE_INLINE Uint32 |
||||
SDL_Swap32(Uint32 x) |
||||
{ |
||||
return SDL_static_cast(Uint32, ((x << 24) | ((x << 8) & 0x00FF0000) | |
||||
((x >> 8) & 0x0000FF00) | (x >> 24))); |
||||
} |
||||
#endif |
||||
|
||||
#if defined(__GNUC__) && defined(__i386__) |
||||
SDL_FORCE_INLINE Uint64 |
||||
SDL_Swap64(Uint64 x) |
||||
{ |
||||
union |
||||
{ |
||||
struct |
||||
{ |
||||
Uint32 a, b; |
||||
} s; |
||||
Uint64 u; |
||||
} v; |
||||
v.u = x; |
||||
__asm__("bswapl %0 ; bswapl %1 ; xchgl %0,%1": "=r"(v.s.a), "=r"(v.s.b):"0"(v.s.a), |
||||
"1"(v.s. |
||||
b)); |
||||
return v.u; |
||||
} |
||||
#elif defined(__GNUC__) && defined(__x86_64__) |
||||
SDL_FORCE_INLINE Uint64 |
||||
SDL_Swap64(Uint64 x) |
||||
{ |
||||
__asm__("bswapq %0": "=r"(x):"0"(x)); |
||||
return x; |
||||
} |
||||
#else |
||||
SDL_FORCE_INLINE Uint64 |
||||
SDL_Swap64(Uint64 x) |
||||
{ |
||||
Uint32 hi, lo; |
||||
|
||||
/* Separate into high and low 32-bit values and swap them */ |
||||
lo = SDL_static_cast(Uint32, x & 0xFFFFFFFF); |
||||
x >>= 32; |
||||
hi = SDL_static_cast(Uint32, x & 0xFFFFFFFF); |
||||
x = SDL_Swap32(lo); |
||||
x <<= 32; |
||||
x |= SDL_Swap32(hi); |
||||
return (x); |
||||
} |
||||
#endif |
||||
|
||||
|
||||
SDL_FORCE_INLINE float |
||||
SDL_SwapFloat(float x) |
||||
{ |
||||
union |
||||
{ |
||||
float f; |
||||
Uint32 ui32; |
||||
} swapper; |
||||
swapper.f = x; |
||||
swapper.ui32 = SDL_Swap32(swapper.ui32); |
||||
return swapper.f; |
||||
} |
||||
|
||||
|
||||
/**
|
||||
* \name Swap to native |
||||
* Byteswap item from the specified endianness to the native endianness. |
||||
*/ |
||||
/* @{ */ |
||||
#if SDL_BYTEORDER == SDL_LIL_ENDIAN |
||||
#define SDL_SwapLE16(X) (X) |
||||
#define SDL_SwapLE32(X) (X) |
||||
#define SDL_SwapLE64(X) (X) |
||||
#define SDL_SwapFloatLE(X) (X) |
||||
#define SDL_SwapBE16(X) SDL_Swap16(X) |
||||
#define SDL_SwapBE32(X) SDL_Swap32(X) |
||||
#define SDL_SwapBE64(X) SDL_Swap64(X) |
||||
#define SDL_SwapFloatBE(X) SDL_SwapFloat(X) |
||||
#else |
||||
#define SDL_SwapLE16(X) SDL_Swap16(X) |
||||
#define SDL_SwapLE32(X) SDL_Swap32(X) |
||||
#define SDL_SwapLE64(X) SDL_Swap64(X) |
||||
#define SDL_SwapFloatLE(X) SDL_SwapFloat(X) |
||||
#define SDL_SwapBE16(X) (X) |
||||
#define SDL_SwapBE32(X) (X) |
||||
#define SDL_SwapBE64(X) (X) |
||||
#define SDL_SwapFloatBE(X) (X) |
||||
#endif |
||||
/* @} *//* Swap to native */ |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_endian_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,76 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_error.h |
||||
* |
||||
* Simple error message routines for SDL. |
||||
*/ |
||||
|
||||
#ifndef SDL_error_h_ |
||||
#define SDL_error_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* Public functions */ |
||||
/* SDL_SetError() unconditionally returns -1. */ |
||||
extern DECLSPEC int SDLCALL SDL_SetError(SDL_PRINTF_FORMAT_STRING const char *fmt, ...) SDL_PRINTF_VARARG_FUNC(1); |
||||
extern DECLSPEC const char *SDLCALL SDL_GetError(void); |
||||
extern DECLSPEC void SDLCALL SDL_ClearError(void); |
||||
|
||||
/**
|
||||
* \name Internal error functions |
||||
* |
||||
* \internal |
||||
* Private error reporting function - used internally. |
||||
*/ |
||||
/* @{ */ |
||||
#define SDL_OutOfMemory() SDL_Error(SDL_ENOMEM) |
||||
#define SDL_Unsupported() SDL_Error(SDL_UNSUPPORTED) |
||||
#define SDL_InvalidParamError(param) SDL_SetError("Parameter '%s' is invalid", (param)) |
||||
typedef enum |
||||
{ |
||||
SDL_ENOMEM, |
||||
SDL_EFREAD, |
||||
SDL_EFWRITE, |
||||
SDL_EFSEEK, |
||||
SDL_UNSUPPORTED, |
||||
SDL_LASTERROR |
||||
} SDL_errorcode; |
||||
/* SDL_Error() unconditionally returns -1. */ |
||||
extern DECLSPEC int SDLCALL SDL_Error(SDL_errorcode code); |
||||
/* @} *//* Internal error functions */ |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_error_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,791 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_events.h |
||||
* |
||||
* Include file for SDL event handling. |
||||
*/ |
||||
|
||||
#ifndef SDL_events_h_ |
||||
#define SDL_events_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
#include "SDL_video.h" |
||||
#include "SDL_keyboard.h" |
||||
#include "SDL_mouse.h" |
||||
#include "SDL_joystick.h" |
||||
#include "SDL_gamecontroller.h" |
||||
#include "SDL_quit.h" |
||||
#include "SDL_gesture.h" |
||||
#include "SDL_touch.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* General keyboard/mouse state definitions */ |
||||
#define SDL_RELEASED 0 |
||||
#define SDL_PRESSED 1 |
||||
|
||||
/**
|
||||
* \brief The types of events that can be delivered. |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_FIRSTEVENT = 0, /**< Unused (do not remove) */ |
||||
|
||||
/* Application events */ |
||||
SDL_QUIT = 0x100, /**< User-requested quit */ |
||||
|
||||
/* These application events have special meaning on iOS, see README-ios.md for details */ |
||||
SDL_APP_TERMINATING, /**< The application is being terminated by the OS
|
||||
Called on iOS in applicationWillTerminate() |
||||
Called on Android in onDestroy() |
||||
*/ |
||||
SDL_APP_LOWMEMORY, /**< The application is low on memory, free memory if possible.
|
||||
Called on iOS in applicationDidReceiveMemoryWarning() |
||||
Called on Android in onLowMemory() |
||||
*/ |
||||
SDL_APP_WILLENTERBACKGROUND, /**< The application is about to enter the background
|
||||
Called on iOS in applicationWillResignActive() |
||||
Called on Android in onPause() |
||||
*/ |
||||
SDL_APP_DIDENTERBACKGROUND, /**< The application did enter the background and may not get CPU for some time
|
||||
Called on iOS in applicationDidEnterBackground() |
||||
Called on Android in onPause() |
||||
*/ |
||||
SDL_APP_WILLENTERFOREGROUND, /**< The application is about to enter the foreground
|
||||
Called on iOS in applicationWillEnterForeground() |
||||
Called on Android in onResume() |
||||
*/ |
||||
SDL_APP_DIDENTERFOREGROUND, /**< The application is now interactive
|
||||
Called on iOS in applicationDidBecomeActive() |
||||
Called on Android in onResume() |
||||
*/ |
||||
|
||||
/* Display events */ |
||||
SDL_DISPLAYEVENT = 0x150, /**< Display state change */ |
||||
|
||||
/* Window events */ |
||||
SDL_WINDOWEVENT = 0x200, /**< Window state change */ |
||||
SDL_SYSWMEVENT, /**< System specific event */ |
||||
|
||||
/* Keyboard events */ |
||||
SDL_KEYDOWN = 0x300, /**< Key pressed */ |
||||
SDL_KEYUP, /**< Key released */ |
||||
SDL_TEXTEDITING, /**< Keyboard text editing (composition) */ |
||||
SDL_TEXTINPUT, /**< Keyboard text input */ |
||||
SDL_KEYMAPCHANGED, /**< Keymap changed due to a system event such as an
|
||||
input language or keyboard layout change. |
||||
*/ |
||||
|
||||
/* Mouse events */ |
||||
SDL_MOUSEMOTION = 0x400, /**< Mouse moved */ |
||||
SDL_MOUSEBUTTONDOWN, /**< Mouse button pressed */ |
||||
SDL_MOUSEBUTTONUP, /**< Mouse button released */ |
||||
SDL_MOUSEWHEEL, /**< Mouse wheel motion */ |
||||
|
||||
/* Joystick events */ |
||||
SDL_JOYAXISMOTION = 0x600, /**< Joystick axis motion */ |
||||
SDL_JOYBALLMOTION, /**< Joystick trackball motion */ |
||||
SDL_JOYHATMOTION, /**< Joystick hat position change */ |
||||
SDL_JOYBUTTONDOWN, /**< Joystick button pressed */ |
||||
SDL_JOYBUTTONUP, /**< Joystick button released */ |
||||
SDL_JOYDEVICEADDED, /**< A new joystick has been inserted into the system */ |
||||
SDL_JOYDEVICEREMOVED, /**< An opened joystick has been removed */ |
||||
|
||||
/* Game controller events */ |
||||
SDL_CONTROLLERAXISMOTION = 0x650, /**< Game controller axis motion */ |
||||
SDL_CONTROLLERBUTTONDOWN, /**< Game controller button pressed */ |
||||
SDL_CONTROLLERBUTTONUP, /**< Game controller button released */ |
||||
SDL_CONTROLLERDEVICEADDED, /**< A new Game controller has been inserted into the system */ |
||||
SDL_CONTROLLERDEVICEREMOVED, /**< An opened Game controller has been removed */ |
||||
SDL_CONTROLLERDEVICEREMAPPED, /**< The controller mapping was updated */ |
||||
|
||||
/* Touch events */ |
||||
SDL_FINGERDOWN = 0x700, |
||||
SDL_FINGERUP, |
||||
SDL_FINGERMOTION, |
||||
|
||||
/* Gesture events */ |
||||
SDL_DOLLARGESTURE = 0x800, |
||||
SDL_DOLLARRECORD, |
||||
SDL_MULTIGESTURE, |
||||
|
||||
/* Clipboard events */ |
||||
SDL_CLIPBOARDUPDATE = 0x900, /**< The clipboard changed */ |
||||
|
||||
/* Drag and drop events */ |
||||
SDL_DROPFILE = 0x1000, /**< The system requests a file open */ |
||||
SDL_DROPTEXT, /**< text/plain drag-and-drop event */ |
||||
SDL_DROPBEGIN, /**< A new set of drops is beginning (NULL filename) */ |
||||
SDL_DROPCOMPLETE, /**< Current set of drops is now complete (NULL filename) */ |
||||
|
||||
/* Audio hotplug events */ |
||||
SDL_AUDIODEVICEADDED = 0x1100, /**< A new audio device is available */ |
||||
SDL_AUDIODEVICEREMOVED, /**< An audio device has been removed. */ |
||||
|
||||
/* Sensor events */ |
||||
SDL_SENSORUPDATE = 0x1200, /**< A sensor was updated */ |
||||
|
||||
/* Render events */ |
||||
SDL_RENDER_TARGETS_RESET = 0x2000, /**< The render targets have been reset and their contents need to be updated */ |
||||
SDL_RENDER_DEVICE_RESET, /**< The device has been reset and all textures need to be recreated */ |
||||
|
||||
/** Events ::SDL_USEREVENT through ::SDL_LASTEVENT are for your use,
|
||||
* and should be allocated with SDL_RegisterEvents() |
||||
*/ |
||||
SDL_USEREVENT = 0x8000, |
||||
|
||||
/**
|
||||
* This last event is only for bounding internal arrays |
||||
*/ |
||||
SDL_LASTEVENT = 0xFFFF |
||||
} SDL_EventType; |
||||
|
||||
/**
|
||||
* \brief Fields shared by every event |
||||
*/ |
||||
typedef struct SDL_CommonEvent |
||||
{ |
||||
Uint32 type; |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
} SDL_CommonEvent; |
||||
|
||||
/**
|
||||
* \brief Display state change event data (event.display.*) |
||||
*/ |
||||
typedef struct SDL_DisplayEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_DISPLAYEVENT */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Uint32 display; /**< The associated display index */ |
||||
Uint8 event; /**< ::SDL_DisplayEventID */ |
||||
Uint8 padding1; |
||||
Uint8 padding2; |
||||
Uint8 padding3; |
||||
Sint32 data1; /**< event dependent data */ |
||||
} SDL_DisplayEvent; |
||||
|
||||
/**
|
||||
* \brief Window state change event data (event.window.*) |
||||
*/ |
||||
typedef struct SDL_WindowEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_WINDOWEVENT */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Uint32 windowID; /**< The associated window */ |
||||
Uint8 event; /**< ::SDL_WindowEventID */ |
||||
Uint8 padding1; |
||||
Uint8 padding2; |
||||
Uint8 padding3; |
||||
Sint32 data1; /**< event dependent data */ |
||||
Sint32 data2; /**< event dependent data */ |
||||
} SDL_WindowEvent; |
||||
|
||||
/**
|
||||
* \brief Keyboard button event structure (event.key.*) |
||||
*/ |
||||
typedef struct SDL_KeyboardEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_KEYDOWN or ::SDL_KEYUP */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Uint32 windowID; /**< The window with keyboard focus, if any */ |
||||
Uint8 state; /**< ::SDL_PRESSED or ::SDL_RELEASED */ |
||||
Uint8 repeat; /**< Non-zero if this is a key repeat */ |
||||
Uint8 padding2; |
||||
Uint8 padding3; |
||||
SDL_Keysym keysym; /**< The key that was pressed or released */ |
||||
} SDL_KeyboardEvent; |
||||
|
||||
#define SDL_TEXTEDITINGEVENT_TEXT_SIZE (32) |
||||
/**
|
||||
* \brief Keyboard text editing event structure (event.edit.*) |
||||
*/ |
||||
typedef struct SDL_TextEditingEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_TEXTEDITING */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Uint32 windowID; /**< The window with keyboard focus, if any */ |
||||
char text[SDL_TEXTEDITINGEVENT_TEXT_SIZE]; /**< The editing text */ |
||||
Sint32 start; /**< The start cursor of selected editing text */ |
||||
Sint32 length; /**< The length of selected editing text */ |
||||
} SDL_TextEditingEvent; |
||||
|
||||
|
||||
#define SDL_TEXTINPUTEVENT_TEXT_SIZE (32) |
||||
/**
|
||||
* \brief Keyboard text input event structure (event.text.*) |
||||
*/ |
||||
typedef struct SDL_TextInputEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_TEXTINPUT */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Uint32 windowID; /**< The window with keyboard focus, if any */ |
||||
char text[SDL_TEXTINPUTEVENT_TEXT_SIZE]; /**< The input text */ |
||||
} SDL_TextInputEvent; |
||||
|
||||
/**
|
||||
* \brief Mouse motion event structure (event.motion.*) |
||||
*/ |
||||
typedef struct SDL_MouseMotionEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_MOUSEMOTION */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Uint32 windowID; /**< The window with mouse focus, if any */ |
||||
Uint32 which; /**< The mouse instance id, or SDL_TOUCH_MOUSEID */ |
||||
Uint32 state; /**< The current button state */ |
||||
Sint32 x; /**< X coordinate, relative to window */ |
||||
Sint32 y; /**< Y coordinate, relative to window */ |
||||
Sint32 xrel; /**< The relative motion in the X direction */ |
||||
Sint32 yrel; /**< The relative motion in the Y direction */ |
||||
} SDL_MouseMotionEvent; |
||||
|
||||
/**
|
||||
* \brief Mouse button event structure (event.button.*) |
||||
*/ |
||||
typedef struct SDL_MouseButtonEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_MOUSEBUTTONDOWN or ::SDL_MOUSEBUTTONUP */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Uint32 windowID; /**< The window with mouse focus, if any */ |
||||
Uint32 which; /**< The mouse instance id, or SDL_TOUCH_MOUSEID */ |
||||
Uint8 button; /**< The mouse button index */ |
||||
Uint8 state; /**< ::SDL_PRESSED or ::SDL_RELEASED */ |
||||
Uint8 clicks; /**< 1 for single-click, 2 for double-click, etc. */ |
||||
Uint8 padding1; |
||||
Sint32 x; /**< X coordinate, relative to window */ |
||||
Sint32 y; /**< Y coordinate, relative to window */ |
||||
} SDL_MouseButtonEvent; |
||||
|
||||
/**
|
||||
* \brief Mouse wheel event structure (event.wheel.*) |
||||
*/ |
||||
typedef struct SDL_MouseWheelEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_MOUSEWHEEL */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Uint32 windowID; /**< The window with mouse focus, if any */ |
||||
Uint32 which; /**< The mouse instance id, or SDL_TOUCH_MOUSEID */ |
||||
Sint32 x; /**< The amount scrolled horizontally, positive to the right and negative to the left */ |
||||
Sint32 y; /**< The amount scrolled vertically, positive away from the user and negative toward the user */ |
||||
Uint32 direction; /**< Set to one of the SDL_MOUSEWHEEL_* defines. When FLIPPED the values in X and Y will be opposite. Multiply by -1 to change them back */ |
||||
} SDL_MouseWheelEvent; |
||||
|
||||
/**
|
||||
* \brief Joystick axis motion event structure (event.jaxis.*) |
||||
*/ |
||||
typedef struct SDL_JoyAxisEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_JOYAXISMOTION */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
SDL_JoystickID which; /**< The joystick instance id */ |
||||
Uint8 axis; /**< The joystick axis index */ |
||||
Uint8 padding1; |
||||
Uint8 padding2; |
||||
Uint8 padding3; |
||||
Sint16 value; /**< The axis value (range: -32768 to 32767) */ |
||||
Uint16 padding4; |
||||
} SDL_JoyAxisEvent; |
||||
|
||||
/**
|
||||
* \brief Joystick trackball motion event structure (event.jball.*) |
||||
*/ |
||||
typedef struct SDL_JoyBallEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_JOYBALLMOTION */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
SDL_JoystickID which; /**< The joystick instance id */ |
||||
Uint8 ball; /**< The joystick trackball index */ |
||||
Uint8 padding1; |
||||
Uint8 padding2; |
||||
Uint8 padding3; |
||||
Sint16 xrel; /**< The relative motion in the X direction */ |
||||
Sint16 yrel; /**< The relative motion in the Y direction */ |
||||
} SDL_JoyBallEvent; |
||||
|
||||
/**
|
||||
* \brief Joystick hat position change event structure (event.jhat.*) |
||||
*/ |
||||
typedef struct SDL_JoyHatEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_JOYHATMOTION */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
SDL_JoystickID which; /**< The joystick instance id */ |
||||
Uint8 hat; /**< The joystick hat index */ |
||||
Uint8 value; /**< The hat position value.
|
||||
* \sa ::SDL_HAT_LEFTUP ::SDL_HAT_UP ::SDL_HAT_RIGHTUP |
||||
* \sa ::SDL_HAT_LEFT ::SDL_HAT_CENTERED ::SDL_HAT_RIGHT |
||||
* \sa ::SDL_HAT_LEFTDOWN ::SDL_HAT_DOWN ::SDL_HAT_RIGHTDOWN |
||||
* |
||||
* Note that zero means the POV is centered. |
||||
*/ |
||||
Uint8 padding1; |
||||
Uint8 padding2; |
||||
} SDL_JoyHatEvent; |
||||
|
||||
/**
|
||||
* \brief Joystick button event structure (event.jbutton.*) |
||||
*/ |
||||
typedef struct SDL_JoyButtonEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_JOYBUTTONDOWN or ::SDL_JOYBUTTONUP */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
SDL_JoystickID which; /**< The joystick instance id */ |
||||
Uint8 button; /**< The joystick button index */ |
||||
Uint8 state; /**< ::SDL_PRESSED or ::SDL_RELEASED */ |
||||
Uint8 padding1; |
||||
Uint8 padding2; |
||||
} SDL_JoyButtonEvent; |
||||
|
||||
/**
|
||||
* \brief Joystick device event structure (event.jdevice.*) |
||||
*/ |
||||
typedef struct SDL_JoyDeviceEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_JOYDEVICEADDED or ::SDL_JOYDEVICEREMOVED */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Sint32 which; /**< The joystick device index for the ADDED event, instance id for the REMOVED event */ |
||||
} SDL_JoyDeviceEvent; |
||||
|
||||
|
||||
/**
|
||||
* \brief Game controller axis motion event structure (event.caxis.*) |
||||
*/ |
||||
typedef struct SDL_ControllerAxisEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_CONTROLLERAXISMOTION */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
SDL_JoystickID which; /**< The joystick instance id */ |
||||
Uint8 axis; /**< The controller axis (SDL_GameControllerAxis) */ |
||||
Uint8 padding1; |
||||
Uint8 padding2; |
||||
Uint8 padding3; |
||||
Sint16 value; /**< The axis value (range: -32768 to 32767) */ |
||||
Uint16 padding4; |
||||
} SDL_ControllerAxisEvent; |
||||
|
||||
|
||||
/**
|
||||
* \brief Game controller button event structure (event.cbutton.*) |
||||
*/ |
||||
typedef struct SDL_ControllerButtonEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_CONTROLLERBUTTONDOWN or ::SDL_CONTROLLERBUTTONUP */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
SDL_JoystickID which; /**< The joystick instance id */ |
||||
Uint8 button; /**< The controller button (SDL_GameControllerButton) */ |
||||
Uint8 state; /**< ::SDL_PRESSED or ::SDL_RELEASED */ |
||||
Uint8 padding1; |
||||
Uint8 padding2; |
||||
} SDL_ControllerButtonEvent; |
||||
|
||||
|
||||
/**
|
||||
* \brief Controller device event structure (event.cdevice.*) |
||||
*/ |
||||
typedef struct SDL_ControllerDeviceEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_CONTROLLERDEVICEADDED, ::SDL_CONTROLLERDEVICEREMOVED, or ::SDL_CONTROLLERDEVICEREMAPPED */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Sint32 which; /**< The joystick device index for the ADDED event, instance id for the REMOVED or REMAPPED event */ |
||||
} SDL_ControllerDeviceEvent; |
||||
|
||||
/**
|
||||
* \brief Audio device event structure (event.adevice.*) |
||||
*/ |
||||
typedef struct SDL_AudioDeviceEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_AUDIODEVICEADDED, or ::SDL_AUDIODEVICEREMOVED */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Uint32 which; /**< The audio device index for the ADDED event (valid until next SDL_GetNumAudioDevices() call), SDL_AudioDeviceID for the REMOVED event */ |
||||
Uint8 iscapture; /**< zero if an output device, non-zero if a capture device. */ |
||||
Uint8 padding1; |
||||
Uint8 padding2; |
||||
Uint8 padding3; |
||||
} SDL_AudioDeviceEvent; |
||||
|
||||
|
||||
/**
|
||||
* \brief Touch finger event structure (event.tfinger.*) |
||||
*/ |
||||
typedef struct SDL_TouchFingerEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_FINGERMOTION or ::SDL_FINGERDOWN or ::SDL_FINGERUP */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
SDL_TouchID touchId; /**< The touch device id */ |
||||
SDL_FingerID fingerId; |
||||
float x; /**< Normalized in the range 0...1 */ |
||||
float y; /**< Normalized in the range 0...1 */ |
||||
float dx; /**< Normalized in the range -1...1 */ |
||||
float dy; /**< Normalized in the range -1...1 */ |
||||
float pressure; /**< Normalized in the range 0...1 */ |
||||
} SDL_TouchFingerEvent; |
||||
|
||||
|
||||
/**
|
||||
* \brief Multiple Finger Gesture Event (event.mgesture.*) |
||||
*/ |
||||
typedef struct SDL_MultiGestureEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_MULTIGESTURE */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
SDL_TouchID touchId; /**< The touch device id */ |
||||
float dTheta; |
||||
float dDist; |
||||
float x; |
||||
float y; |
||||
Uint16 numFingers; |
||||
Uint16 padding; |
||||
} SDL_MultiGestureEvent; |
||||
|
||||
|
||||
/**
|
||||
* \brief Dollar Gesture Event (event.dgesture.*) |
||||
*/ |
||||
typedef struct SDL_DollarGestureEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_DOLLARGESTURE or ::SDL_DOLLARRECORD */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
SDL_TouchID touchId; /**< The touch device id */ |
||||
SDL_GestureID gestureId; |
||||
Uint32 numFingers; |
||||
float error; |
||||
float x; /**< Normalized center of gesture */ |
||||
float y; /**< Normalized center of gesture */ |
||||
} SDL_DollarGestureEvent; |
||||
|
||||
|
||||
/**
|
||||
* \brief An event used to request a file open by the system (event.drop.*) |
||||
* This event is enabled by default, you can disable it with SDL_EventState(). |
||||
* \note If this event is enabled, you must free the filename in the event. |
||||
*/ |
||||
typedef struct SDL_DropEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_DROPBEGIN or ::SDL_DROPFILE or ::SDL_DROPTEXT or ::SDL_DROPCOMPLETE */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
char *file; /**< The file name, which should be freed with SDL_free(), is NULL on begin/complete */ |
||||
Uint32 windowID; /**< The window that was dropped on, if any */ |
||||
} SDL_DropEvent; |
||||
|
||||
|
||||
/**
|
||||
* \brief Sensor event structure (event.sensor.*) |
||||
*/ |
||||
typedef struct SDL_SensorEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_SENSORUPDATE */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Sint32 which; /**< The instance ID of the sensor */ |
||||
float data[6]; /**< Up to 6 values from the sensor - additional values can be queried using SDL_SensorGetData() */ |
||||
} SDL_SensorEvent; |
||||
|
||||
/**
|
||||
* \brief The "quit requested" event |
||||
*/ |
||||
typedef struct SDL_QuitEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_QUIT */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
} SDL_QuitEvent; |
||||
|
||||
/**
|
||||
* \brief OS Specific event |
||||
*/ |
||||
typedef struct SDL_OSEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_QUIT */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
} SDL_OSEvent; |
||||
|
||||
/**
|
||||
* \brief A user-defined event type (event.user.*) |
||||
*/ |
||||
typedef struct SDL_UserEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_USEREVENT through ::SDL_LASTEVENT-1 */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
Uint32 windowID; /**< The associated window if any */ |
||||
Sint32 code; /**< User defined event code */ |
||||
void *data1; /**< User defined data pointer */ |
||||
void *data2; /**< User defined data pointer */ |
||||
} SDL_UserEvent; |
||||
|
||||
|
||||
struct SDL_SysWMmsg; |
||||
typedef struct SDL_SysWMmsg SDL_SysWMmsg; |
||||
|
||||
/**
|
||||
* \brief A video driver dependent system event (event.syswm.*) |
||||
* This event is disabled by default, you can enable it with SDL_EventState() |
||||
* |
||||
* \note If you want to use this event, you should include SDL_syswm.h. |
||||
*/ |
||||
typedef struct SDL_SysWMEvent |
||||
{ |
||||
Uint32 type; /**< ::SDL_SYSWMEVENT */ |
||||
Uint32 timestamp; /**< In milliseconds, populated using SDL_GetTicks() */ |
||||
SDL_SysWMmsg *msg; /**< driver dependent data, defined in SDL_syswm.h */ |
||||
} SDL_SysWMEvent; |
||||
|
||||
/**
|
||||
* \brief General event structure |
||||
*/ |
||||
typedef union SDL_Event |
||||
{ |
||||
Uint32 type; /**< Event type, shared with all events */ |
||||
SDL_CommonEvent common; /**< Common event data */ |
||||
SDL_DisplayEvent display; /**< Window event data */ |
||||
SDL_WindowEvent window; /**< Window event data */ |
||||
SDL_KeyboardEvent key; /**< Keyboard event data */ |
||||
SDL_TextEditingEvent edit; /**< Text editing event data */ |
||||
SDL_TextInputEvent text; /**< Text input event data */ |
||||
SDL_MouseMotionEvent motion; /**< Mouse motion event data */ |
||||
SDL_MouseButtonEvent button; /**< Mouse button event data */ |
||||
SDL_MouseWheelEvent wheel; /**< Mouse wheel event data */ |
||||
SDL_JoyAxisEvent jaxis; /**< Joystick axis event data */ |
||||
SDL_JoyBallEvent jball; /**< Joystick ball event data */ |
||||
SDL_JoyHatEvent jhat; /**< Joystick hat event data */ |
||||
SDL_JoyButtonEvent jbutton; /**< Joystick button event data */ |
||||
SDL_JoyDeviceEvent jdevice; /**< Joystick device change event data */ |
||||
SDL_ControllerAxisEvent caxis; /**< Game Controller axis event data */ |
||||
SDL_ControllerButtonEvent cbutton; /**< Game Controller button event data */ |
||||
SDL_ControllerDeviceEvent cdevice; /**< Game Controller device event data */ |
||||
SDL_AudioDeviceEvent adevice; /**< Audio device event data */ |
||||
SDL_SensorEvent sensor; /**< Sensor event data */ |
||||
SDL_QuitEvent quit; /**< Quit request event data */ |
||||
SDL_UserEvent user; /**< Custom event data */ |
||||
SDL_SysWMEvent syswm; /**< System dependent window event data */ |
||||
SDL_TouchFingerEvent tfinger; /**< Touch finger event data */ |
||||
SDL_MultiGestureEvent mgesture; /**< Gesture event data */ |
||||
SDL_DollarGestureEvent dgesture; /**< Gesture event data */ |
||||
SDL_DropEvent drop; /**< Drag and drop event data */ |
||||
|
||||
/* This is necessary for ABI compatibility between Visual C++ and GCC
|
||||
Visual C++ will respect the push pack pragma and use 52 bytes for |
||||
this structure, and GCC will use the alignment of the largest datatype |
||||
within the union, which is 8 bytes. |
||||
|
||||
So... we'll add padding to force the size to be 56 bytes for both. |
||||
*/ |
||||
Uint8 padding[56]; |
||||
} SDL_Event; |
||||
|
||||
/* Make sure we haven't broken binary compatibility */ |
||||
SDL_COMPILE_TIME_ASSERT(SDL_Event, sizeof(SDL_Event) == 56); |
||||
|
||||
|
||||
/* Function prototypes */ |
||||
|
||||
/**
|
||||
* Pumps the event loop, gathering events from the input devices. |
||||
* |
||||
* This function updates the event queue and internal input device state. |
||||
* |
||||
* This should only be run in the thread that sets the video mode. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_PumpEvents(void); |
||||
|
||||
/* @{ */ |
||||
typedef enum |
||||
{ |
||||
SDL_ADDEVENT, |
||||
SDL_PEEKEVENT, |
||||
SDL_GETEVENT |
||||
} SDL_eventaction; |
||||
|
||||
/**
|
||||
* Checks the event queue for messages and optionally returns them. |
||||
* |
||||
* If \c action is ::SDL_ADDEVENT, up to \c numevents events will be added to |
||||
* the back of the event queue. |
||||
* |
||||
* If \c action is ::SDL_PEEKEVENT, up to \c numevents events at the front |
||||
* of the event queue, within the specified minimum and maximum type, |
||||
* will be returned and will not be removed from the queue. |
||||
* |
||||
* If \c action is ::SDL_GETEVENT, up to \c numevents events at the front |
||||
* of the event queue, within the specified minimum and maximum type, |
||||
* will be returned and will be removed from the queue. |
||||
* |
||||
* \return The number of events actually stored, or -1 if there was an error. |
||||
* |
||||
* This function is thread-safe. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_PeepEvents(SDL_Event * events, int numevents, |
||||
SDL_eventaction action, |
||||
Uint32 minType, Uint32 maxType); |
||||
/* @} */ |
||||
|
||||
/**
|
||||
* Checks to see if certain event types are in the event queue. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasEvent(Uint32 type); |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasEvents(Uint32 minType, Uint32 maxType); |
||||
|
||||
/**
|
||||
* This function clears events from the event queue |
||||
* This function only affects currently queued events. If you want to make |
||||
* sure that all pending OS events are flushed, you can call SDL_PumpEvents() |
||||
* on the main thread immediately before the flush call. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_FlushEvent(Uint32 type); |
||||
extern DECLSPEC void SDLCALL SDL_FlushEvents(Uint32 minType, Uint32 maxType); |
||||
|
||||
/**
|
||||
* \brief Polls for currently pending events. |
||||
* |
||||
* \return 1 if there are any pending events, or 0 if there are none available. |
||||
* |
||||
* \param event If not NULL, the next event is removed from the queue and |
||||
* stored in that area. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_PollEvent(SDL_Event * event); |
||||
|
||||
/**
|
||||
* \brief Waits indefinitely for the next available event. |
||||
* |
||||
* \return 1, or 0 if there was an error while waiting for events. |
||||
* |
||||
* \param event If not NULL, the next event is removed from the queue and |
||||
* stored in that area. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_WaitEvent(SDL_Event * event); |
||||
|
||||
/**
|
||||
* \brief Waits until the specified timeout (in milliseconds) for the next |
||||
* available event. |
||||
* |
||||
* \return 1, or 0 if there was an error while waiting for events. |
||||
* |
||||
* \param event If not NULL, the next event is removed from the queue and |
||||
* stored in that area. |
||||
* \param timeout The timeout (in milliseconds) to wait for next event. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_WaitEventTimeout(SDL_Event * event, |
||||
int timeout); |
||||
|
||||
/**
|
||||
* \brief Add an event to the event queue. |
||||
* |
||||
* \return 1 on success, 0 if the event was filtered, or -1 if the event queue |
||||
* was full or there was some other error. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_PushEvent(SDL_Event * event); |
||||
|
||||
typedef int (SDLCALL * SDL_EventFilter) (void *userdata, SDL_Event * event); |
||||
|
||||
/**
|
||||
* Sets up a filter to process all events before they change internal state and |
||||
* are posted to the internal event queue. |
||||
* |
||||
* The filter is prototyped as: |
||||
* \code |
||||
* int SDL_EventFilter(void *userdata, SDL_Event * event); |
||||
* \endcode |
||||
* |
||||
* If the filter returns 1, then the event will be added to the internal queue. |
||||
* If it returns 0, then the event will be dropped from the queue, but the |
||||
* internal state will still be updated. This allows selective filtering of |
||||
* dynamically arriving events. |
||||
* |
||||
* \warning Be very careful of what you do in the event filter function, as |
||||
* it may run in a different thread! |
||||
* |
||||
* There is one caveat when dealing with the ::SDL_QuitEvent event type. The |
||||
* event filter is only called when the window manager desires to close the |
||||
* application window. If the event filter returns 1, then the window will |
||||
* be closed, otherwise the window will remain open if possible. |
||||
* |
||||
* If the quit event is generated by an interrupt signal, it will bypass the |
||||
* internal queue and be delivered to the application at the next event poll. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_SetEventFilter(SDL_EventFilter filter, |
||||
void *userdata); |
||||
|
||||
/**
|
||||
* Return the current event filter - can be used to "chain" filters. |
||||
* If there is no event filter set, this function returns SDL_FALSE. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_GetEventFilter(SDL_EventFilter * filter, |
||||
void **userdata); |
||||
|
||||
/**
|
||||
* Add a function which is called when an event is added to the queue. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_AddEventWatch(SDL_EventFilter filter, |
||||
void *userdata); |
||||
|
||||
/**
|
||||
* Remove an event watch function added with SDL_AddEventWatch() |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_DelEventWatch(SDL_EventFilter filter, |
||||
void *userdata); |
||||
|
||||
/**
|
||||
* Run the filter function on the current event queue, removing any |
||||
* events for which the filter returns 0. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_FilterEvents(SDL_EventFilter filter, |
||||
void *userdata); |
||||
|
||||
/* @{ */ |
||||
#define SDL_QUERY -1 |
||||
#define SDL_IGNORE 0 |
||||
#define SDL_DISABLE 0 |
||||
#define SDL_ENABLE 1 |
||||
|
||||
/**
|
||||
* This function allows you to set the state of processing certain events. |
||||
* - If \c state is set to ::SDL_IGNORE, that event will be automatically |
||||
* dropped from the event queue and will not be filtered. |
||||
* - If \c state is set to ::SDL_ENABLE, that event will be processed |
||||
* normally. |
||||
* - If \c state is set to ::SDL_QUERY, SDL_EventState() will return the |
||||
* current processing state of the specified event. |
||||
*/ |
||||
extern DECLSPEC Uint8 SDLCALL SDL_EventState(Uint32 type, int state); |
||||
/* @} */ |
||||
#define SDL_GetEventState(type) SDL_EventState(type, SDL_QUERY) |
||||
|
||||
/**
|
||||
* This function allocates a set of user-defined events, and returns |
||||
* the beginning event number for that set of events. |
||||
* |
||||
* If there aren't enough user-defined events left, this function |
||||
* returns (Uint32)-1 |
||||
*/ |
||||
extern DECLSPEC Uint32 SDLCALL SDL_RegisterEvents(int numevents); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_events_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,136 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_filesystem.h |
||||
* |
||||
* \brief Include file for filesystem SDL API functions |
||||
*/ |
||||
|
||||
#ifndef SDL_filesystem_h_ |
||||
#define SDL_filesystem_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
|
||||
#include "begin_code.h" |
||||
|
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief Get the path where the application resides. |
||||
* |
||||
* Get the "base path". This is the directory where the application was run |
||||
* from, which is probably the installation directory, and may or may not |
||||
* be the process's current working directory. |
||||
* |
||||
* This returns an absolute path in UTF-8 encoding, and is guaranteed to |
||||
* end with a path separator ('\\' on Windows, '/' most other places). |
||||
* |
||||
* The pointer returned by this function is owned by you. Please call |
||||
* SDL_free() on the pointer when you are done with it, or it will be a |
||||
* memory leak. This is not necessarily a fast call, though, so you should |
||||
* call this once near startup and save the string if you need it. |
||||
* |
||||
* Some platforms can't determine the application's path, and on other |
||||
* platforms, this might be meaningless. In such cases, this function will |
||||
* return NULL. |
||||
* |
||||
* \return String of base dir in UTF-8 encoding, or NULL on error. |
||||
* |
||||
* \sa SDL_GetPrefPath |
||||
*/ |
||||
extern DECLSPEC char *SDLCALL SDL_GetBasePath(void); |
||||
|
||||
/**
|
||||
* \brief Get the user-and-app-specific path where files can be written. |
||||
* |
||||
* Get the "pref dir". This is meant to be where users can write personal |
||||
* files (preferences and save games, etc) that are specific to your |
||||
* application. This directory is unique per user, per application. |
||||
* |
||||
* This function will decide the appropriate location in the native filesystem, |
||||
* create the directory if necessary, and return a string of the absolute |
||||
* path to the directory in UTF-8 encoding. |
||||
* |
||||
* On Windows, the string might look like: |
||||
* "C:\\Users\\bob\\AppData\\Roaming\\My Company\\My Program Name\\" |
||||
* |
||||
* On Linux, the string might look like: |
||||
* "/home/bob/.local/share/My Program Name/" |
||||
* |
||||
* On Mac OS X, the string might look like: |
||||
* "/Users/bob/Library/Application Support/My Program Name/" |
||||
* |
||||
* (etc.) |
||||
* |
||||
* You specify the name of your organization (if it's not a real organization, |
||||
* your name or an Internet domain you own might do) and the name of your |
||||
* application. These should be untranslated proper names. |
||||
* |
||||
* Both the org and app strings may become part of a directory name, so |
||||
* please follow these rules: |
||||
* |
||||
* - Try to use the same org string (including case-sensitivity) for |
||||
* all your applications that use this function. |
||||
* - Always use a unique app string for each one, and make sure it never |
||||
* changes for an app once you've decided on it. |
||||
* - Unicode characters are legal, as long as it's UTF-8 encoded, but... |
||||
* - ...only use letters, numbers, and spaces. Avoid punctuation like |
||||
* "Game Name 2: Bad Guy's Revenge!" ... "Game Name 2" is sufficient. |
||||
* |
||||
* This returns an absolute path in UTF-8 encoding, and is guaranteed to |
||||
* end with a path separator ('\\' on Windows, '/' most other places). |
||||
* |
||||
* The pointer returned by this function is owned by you. Please call |
||||
* SDL_free() on the pointer when you are done with it, or it will be a |
||||
* memory leak. This is not necessarily a fast call, though, so you should |
||||
* call this once near startup and save the string if you need it. |
||||
* |
||||
* You should assume the path returned by this function is the only safe |
||||
* place to write files (and that SDL_GetBasePath(), while it might be |
||||
* writable, or even the parent of the returned path, aren't where you |
||||
* should be writing things). |
||||
* |
||||
* Some platforms can't determine the pref path, and on other |
||||
* platforms, this might be meaningless. In such cases, this function will |
||||
* return NULL. |
||||
* |
||||
* \param org The name of your organization. |
||||
* \param app The name of your application. |
||||
* \return UTF-8 string of user dir in platform-dependent notation. NULL |
||||
* if there's a problem (creating directory failed, etc). |
||||
* |
||||
* \sa SDL_GetBasePath |
||||
*/ |
||||
extern DECLSPEC char *SDLCALL SDL_GetPrefPath(const char *org, const char *app); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_filesystem_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,390 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_gamecontroller.h |
||||
* |
||||
* Include file for SDL game controller event handling |
||||
*/ |
||||
|
||||
#ifndef SDL_gamecontroller_h_ |
||||
#define SDL_gamecontroller_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
#include "SDL_rwops.h" |
||||
#include "SDL_joystick.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \file SDL_gamecontroller.h |
||||
* |
||||
* In order to use these functions, SDL_Init() must have been called |
||||
* with the ::SDL_INIT_GAMECONTROLLER flag. This causes SDL to scan the system |
||||
* for game controllers, and load appropriate drivers. |
||||
* |
||||
* If you would like to receive controller updates while the application |
||||
* is in the background, you should set the following hint before calling |
||||
* SDL_Init(): SDL_HINT_JOYSTICK_ALLOW_BACKGROUND_EVENTS |
||||
*/ |
||||
|
||||
/**
|
||||
* The gamecontroller structure used to identify an SDL game controller |
||||
*/ |
||||
struct _SDL_GameController; |
||||
typedef struct _SDL_GameController SDL_GameController; |
||||
|
||||
|
||||
typedef enum |
||||
{ |
||||
SDL_CONTROLLER_BINDTYPE_NONE = 0, |
||||
SDL_CONTROLLER_BINDTYPE_BUTTON, |
||||
SDL_CONTROLLER_BINDTYPE_AXIS, |
||||
SDL_CONTROLLER_BINDTYPE_HAT |
||||
} SDL_GameControllerBindType; |
||||
|
||||
/**
|
||||
* Get the SDL joystick layer binding for this controller button/axis mapping |
||||
*/ |
||||
typedef struct SDL_GameControllerButtonBind |
||||
{ |
||||
SDL_GameControllerBindType bindType; |
||||
union |
||||
{ |
||||
int button; |
||||
int axis; |
||||
struct { |
||||
int hat; |
||||
int hat_mask; |
||||
} hat; |
||||
} value; |
||||
|
||||
} SDL_GameControllerButtonBind; |
||||
|
||||
|
||||
/**
|
||||
* To count the number of game controllers in the system for the following: |
||||
* int nJoysticks = SDL_NumJoysticks(); |
||||
* int nGameControllers = 0; |
||||
* for (int i = 0; i < nJoysticks; i++) { |
||||
* if (SDL_IsGameController(i)) { |
||||
* nGameControllers++; |
||||
* } |
||||
* } |
||||
* |
||||
* Using the SDL_HINT_GAMECONTROLLERCONFIG hint or the SDL_GameControllerAddMapping() you can add support for controllers SDL is unaware of or cause an existing controller to have a different binding. The format is: |
||||
* guid,name,mappings |
||||
* |
||||
* Where GUID is the string value from SDL_JoystickGetGUIDString(), name is the human readable string for the device and mappings are controller mappings to joystick ones. |
||||
* Under Windows there is a reserved GUID of "xinput" that covers any XInput devices. |
||||
* The mapping format for joystick is: |
||||
* bX - a joystick button, index X |
||||
* hX.Y - hat X with value Y |
||||
* aX - axis X of the joystick |
||||
* Buttons can be used as a controller axis and vice versa. |
||||
* |
||||
* This string shows an example of a valid mapping for a controller |
||||
* "03000000341a00003608000000000000,PS3 Controller,a:b1,b:b2,y:b3,x:b0,start:b9,guide:b12,back:b8,dpup:h0.1,dpleft:h0.8,dpdown:h0.4,dpright:h0.2,leftshoulder:b4,rightshoulder:b5,leftstick:b10,rightstick:b11,leftx:a0,lefty:a1,rightx:a2,righty:a3,lefttrigger:b6,righttrigger:b7", |
||||
* |
||||
*/ |
||||
|
||||
/**
|
||||
* Load a set of mappings from a seekable SDL data stream (memory or file), filtered by the current SDL_GetPlatform() |
||||
* A community sourced database of controllers is available at https://raw.github.com/gabomdq/SDL_GameControllerDB/master/gamecontrollerdb.txt
|
||||
* |
||||
* If \c freerw is non-zero, the stream will be closed after being read. |
||||
*
|
||||
* \return number of mappings added, -1 on error |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GameControllerAddMappingsFromRW(SDL_RWops * rw, int freerw); |
||||
|
||||
/**
|
||||
* Load a set of mappings from a file, filtered by the current SDL_GetPlatform() |
||||
* |
||||
* Convenience macro. |
||||
*/ |
||||
#define SDL_GameControllerAddMappingsFromFile(file) SDL_GameControllerAddMappingsFromRW(SDL_RWFromFile(file, "rb"), 1) |
||||
|
||||
/**
|
||||
* Add or update an existing mapping configuration |
||||
* |
||||
* \return 1 if mapping is added, 0 if updated, -1 on error |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GameControllerAddMapping(const char* mappingString); |
||||
|
||||
/**
|
||||
* Get the number of mappings installed |
||||
* |
||||
* \return the number of mappings |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GameControllerNumMappings(void); |
||||
|
||||
/**
|
||||
* Get the mapping at a particular index. |
||||
* |
||||
* \return the mapping string. Must be freed with SDL_free(). Returns NULL if the index is out of range. |
||||
*/ |
||||
extern DECLSPEC char * SDLCALL SDL_GameControllerMappingForIndex(int mapping_index); |
||||
|
||||
/**
|
||||
* Get a mapping string for a GUID |
||||
* |
||||
* \return the mapping string. Must be freed with SDL_free(). Returns NULL if no mapping is available |
||||
*/ |
||||
extern DECLSPEC char * SDLCALL SDL_GameControllerMappingForGUID(SDL_JoystickGUID guid); |
||||
|
||||
/**
|
||||
* Get a mapping string for an open GameController |
||||
* |
||||
* \return the mapping string. Must be freed with SDL_free(). Returns NULL if no mapping is available |
||||
*/ |
||||
extern DECLSPEC char * SDLCALL SDL_GameControllerMapping(SDL_GameController * gamecontroller); |
||||
|
||||
/**
|
||||
* Is the joystick on this index supported by the game controller interface? |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_IsGameController(int joystick_index); |
||||
|
||||
/**
|
||||
* Get the implementation dependent name of a game controller. |
||||
* This can be called before any controllers are opened. |
||||
* If no name can be found, this function returns NULL. |
||||
*/ |
||||
extern DECLSPEC const char *SDLCALL SDL_GameControllerNameForIndex(int joystick_index); |
||||
|
||||
/**
|
||||
* Get the mapping of a game controller. |
||||
* This can be called before any controllers are opened. |
||||
* |
||||
* \return the mapping string. Must be freed with SDL_free(). Returns NULL if no mapping is available |
||||
*/ |
||||
extern DECLSPEC char *SDLCALL SDL_GameControllerMappingForDeviceIndex(int joystick_index); |
||||
|
||||
/**
|
||||
* Open a game controller for use. |
||||
* The index passed as an argument refers to the N'th game controller on the system. |
||||
* This index is not the value which will identify this controller in future |
||||
* controller events. The joystick's instance id (::SDL_JoystickID) will be |
||||
* used there instead. |
||||
* |
||||
* \return A controller identifier, or NULL if an error occurred. |
||||
*/ |
||||
extern DECLSPEC SDL_GameController *SDLCALL SDL_GameControllerOpen(int joystick_index); |
||||
|
||||
/**
|
||||
* Return the SDL_GameController associated with an instance id. |
||||
*/ |
||||
extern DECLSPEC SDL_GameController *SDLCALL SDL_GameControllerFromInstanceID(SDL_JoystickID joyid); |
||||
|
||||
/**
|
||||
* Return the name for this currently opened controller |
||||
*/ |
||||
extern DECLSPEC const char *SDLCALL SDL_GameControllerName(SDL_GameController *gamecontroller); |
||||
|
||||
/**
|
||||
* Get the player index of an opened game controller, or -1 if it's not available |
||||
* |
||||
* For XInput controllers this returns the XInput user index. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GameControllerGetPlayerIndex(SDL_GameController *gamecontroller); |
||||
|
||||
/**
|
||||
* Get the USB vendor ID of an opened controller, if available. |
||||
* If the vendor ID isn't available this function returns 0. |
||||
*/ |
||||
extern DECLSPEC Uint16 SDLCALL SDL_GameControllerGetVendor(SDL_GameController * gamecontroller); |
||||
|
||||
/**
|
||||
* Get the USB product ID of an opened controller, if available. |
||||
* If the product ID isn't available this function returns 0. |
||||
*/ |
||||
extern DECLSPEC Uint16 SDLCALL SDL_GameControllerGetProduct(SDL_GameController * gamecontroller); |
||||
|
||||
/**
|
||||
* Get the product version of an opened controller, if available. |
||||
* If the product version isn't available this function returns 0. |
||||
*/ |
||||
extern DECLSPEC Uint16 SDLCALL SDL_GameControllerGetProductVersion(SDL_GameController * gamecontroller); |
||||
|
||||
/**
|
||||
* Returns SDL_TRUE if the controller has been opened and currently connected, |
||||
* or SDL_FALSE if it has not. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_GameControllerGetAttached(SDL_GameController *gamecontroller); |
||||
|
||||
/**
|
||||
* Get the underlying joystick object used by a controller |
||||
*/ |
||||
extern DECLSPEC SDL_Joystick *SDLCALL SDL_GameControllerGetJoystick(SDL_GameController *gamecontroller); |
||||
|
||||
/**
|
||||
* Enable/disable controller event polling. |
||||
* |
||||
* If controller events are disabled, you must call SDL_GameControllerUpdate() |
||||
* yourself and check the state of the controller when you want controller |
||||
* information. |
||||
* |
||||
* The state can be one of ::SDL_QUERY, ::SDL_ENABLE or ::SDL_IGNORE. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GameControllerEventState(int state); |
||||
|
||||
/**
|
||||
* Update the current state of the open game controllers. |
||||
* |
||||
* This is called automatically by the event loop if any game controller |
||||
* events are enabled. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_GameControllerUpdate(void); |
||||
|
||||
|
||||
/**
|
||||
* The list of axes available from a controller |
||||
* |
||||
* Thumbstick axis values range from SDL_JOYSTICK_AXIS_MIN to SDL_JOYSTICK_AXIS_MAX, |
||||
* and are centered within ~8000 of zero, though advanced UI will allow users to set |
||||
* or autodetect the dead zone, which varies between controllers. |
||||
* |
||||
* Trigger axis values range from 0 to SDL_JOYSTICK_AXIS_MAX. |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_CONTROLLER_AXIS_INVALID = -1, |
||||
SDL_CONTROLLER_AXIS_LEFTX, |
||||
SDL_CONTROLLER_AXIS_LEFTY, |
||||
SDL_CONTROLLER_AXIS_RIGHTX, |
||||
SDL_CONTROLLER_AXIS_RIGHTY, |
||||
SDL_CONTROLLER_AXIS_TRIGGERLEFT, |
||||
SDL_CONTROLLER_AXIS_TRIGGERRIGHT, |
||||
SDL_CONTROLLER_AXIS_MAX |
||||
} SDL_GameControllerAxis; |
||||
|
||||
/**
|
||||
* turn this string into a axis mapping |
||||
*/ |
||||
extern DECLSPEC SDL_GameControllerAxis SDLCALL SDL_GameControllerGetAxisFromString(const char *pchString); |
||||
|
||||
/**
|
||||
* turn this axis enum into a string mapping |
||||
*/ |
||||
extern DECLSPEC const char* SDLCALL SDL_GameControllerGetStringForAxis(SDL_GameControllerAxis axis); |
||||
|
||||
/**
|
||||
* Get the SDL joystick layer binding for this controller button mapping |
||||
*/ |
||||
extern DECLSPEC SDL_GameControllerButtonBind SDLCALL |
||||
SDL_GameControllerGetBindForAxis(SDL_GameController *gamecontroller, |
||||
SDL_GameControllerAxis axis); |
||||
|
||||
/**
|
||||
* Get the current state of an axis control on a game controller. |
||||
* |
||||
* The state is a value ranging from -32768 to 32767 (except for the triggers, |
||||
* which range from 0 to 32767). |
||||
* |
||||
* The axis indices start at index 0. |
||||
*/ |
||||
extern DECLSPEC Sint16 SDLCALL |
||||
SDL_GameControllerGetAxis(SDL_GameController *gamecontroller, |
||||
SDL_GameControllerAxis axis); |
||||
|
||||
/**
|
||||
* The list of buttons available from a controller |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_CONTROLLER_BUTTON_INVALID = -1, |
||||
SDL_CONTROLLER_BUTTON_A, |
||||
SDL_CONTROLLER_BUTTON_B, |
||||
SDL_CONTROLLER_BUTTON_X, |
||||
SDL_CONTROLLER_BUTTON_Y, |
||||
SDL_CONTROLLER_BUTTON_BACK, |
||||
SDL_CONTROLLER_BUTTON_GUIDE, |
||||
SDL_CONTROLLER_BUTTON_START, |
||||
SDL_CONTROLLER_BUTTON_LEFTSTICK, |
||||
SDL_CONTROLLER_BUTTON_RIGHTSTICK, |
||||
SDL_CONTROLLER_BUTTON_LEFTSHOULDER, |
||||
SDL_CONTROLLER_BUTTON_RIGHTSHOULDER, |
||||
SDL_CONTROLLER_BUTTON_DPAD_UP, |
||||
SDL_CONTROLLER_BUTTON_DPAD_DOWN, |
||||
SDL_CONTROLLER_BUTTON_DPAD_LEFT, |
||||
SDL_CONTROLLER_BUTTON_DPAD_RIGHT, |
||||
SDL_CONTROLLER_BUTTON_MAX |
||||
} SDL_GameControllerButton; |
||||
|
||||
/**
|
||||
* turn this string into a button mapping |
||||
*/ |
||||
extern DECLSPEC SDL_GameControllerButton SDLCALL SDL_GameControllerGetButtonFromString(const char *pchString); |
||||
|
||||
/**
|
||||
* turn this button enum into a string mapping |
||||
*/ |
||||
extern DECLSPEC const char* SDLCALL SDL_GameControllerGetStringForButton(SDL_GameControllerButton button); |
||||
|
||||
/**
|
||||
* Get the SDL joystick layer binding for this controller button mapping |
||||
*/ |
||||
extern DECLSPEC SDL_GameControllerButtonBind SDLCALL |
||||
SDL_GameControllerGetBindForButton(SDL_GameController *gamecontroller, |
||||
SDL_GameControllerButton button); |
||||
|
||||
|
||||
/**
|
||||
* Get the current state of a button on a game controller. |
||||
* |
||||
* The button indices start at index 0. |
||||
*/ |
||||
extern DECLSPEC Uint8 SDLCALL SDL_GameControllerGetButton(SDL_GameController *gamecontroller, |
||||
SDL_GameControllerButton button); |
||||
|
||||
/**
|
||||
* Trigger a rumble effect |
||||
* Each call to this function cancels any previous rumble effect, and calling it with 0 intensity stops any rumbling. |
||||
* |
||||
* \param gamecontroller The controller to vibrate |
||||
* \param low_frequency_rumble The intensity of the low frequency (left) rumble motor, from 0 to 0xFFFF |
||||
* \param high_frequency_rumble The intensity of the high frequency (right) rumble motor, from 0 to 0xFFFF |
||||
* \param duration_ms The duration of the rumble effect, in milliseconds |
||||
* |
||||
* \return 0, or -1 if rumble isn't supported on this joystick |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GameControllerRumble(SDL_GameController *gamecontroller, Uint16 low_frequency_rumble, Uint16 high_frequency_rumble, Uint32 duration_ms); |
||||
|
||||
/**
|
||||
* Close a controller previously opened with SDL_GameControllerOpen(). |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_GameControllerClose(SDL_GameController *gamecontroller); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_gamecontroller_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,87 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_gesture.h |
||||
* |
||||
* Include file for SDL gesture event handling. |
||||
*/ |
||||
|
||||
#ifndef SDL_gesture_h_ |
||||
#define SDL_gesture_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
#include "SDL_video.h" |
||||
|
||||
#include "SDL_touch.h" |
||||
|
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
typedef Sint64 SDL_GestureID; |
||||
|
||||
/* Function prototypes */ |
||||
|
||||
/**
|
||||
* \brief Begin Recording a gesture on the specified touch, or all touches (-1) |
||||
* |
||||
* |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_RecordGesture(SDL_TouchID touchId); |
||||
|
||||
|
||||
/**
|
||||
* \brief Save all currently loaded Dollar Gesture templates |
||||
* |
||||
* |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SaveAllDollarTemplates(SDL_RWops *dst); |
||||
|
||||
/**
|
||||
* \brief Save a currently loaded Dollar Gesture template |
||||
* |
||||
* |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SaveDollarTemplate(SDL_GestureID gestureId,SDL_RWops *dst); |
||||
|
||||
|
||||
/**
|
||||
* \brief Load Dollar Gesture templates from a file |
||||
* |
||||
* |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_LoadDollarTemplates(SDL_TouchID touchId, SDL_RWops *src); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_gesture_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,408 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_joystick.h |
||||
* |
||||
* Include file for SDL joystick event handling |
||||
* |
||||
* The term "device_index" identifies currently plugged in joystick devices between 0 and SDL_NumJoysticks(), with the exact joystick |
||||
* behind a device_index changing as joysticks are plugged and unplugged. |
||||
* |
||||
* The term "instance_id" is the current instantiation of a joystick device in the system, if the joystick is removed and then re-inserted |
||||
* then it will get a new instance_id, instance_id's are monotonically increasing identifiers of a joystick plugged in. |
||||
* |
||||
* The term JoystickGUID is a stable 128-bit identifier for a joystick device that does not change over time, it identifies class of |
||||
* the device (a X360 wired controller for example). This identifier is platform dependent. |
||||
* |
||||
* |
||||
*/ |
||||
|
||||
#ifndef SDL_joystick_h_ |
||||
#define SDL_joystick_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \file SDL_joystick.h |
||||
* |
||||
* In order to use these functions, SDL_Init() must have been called |
||||
* with the ::SDL_INIT_JOYSTICK flag. This causes SDL to scan the system |
||||
* for joysticks, and load appropriate drivers. |
||||
* |
||||
* If you would like to receive joystick updates while the application |
||||
* is in the background, you should set the following hint before calling |
||||
* SDL_Init(): SDL_HINT_JOYSTICK_ALLOW_BACKGROUND_EVENTS |
||||
*/ |
||||
|
||||
/**
|
||||
* The joystick structure used to identify an SDL joystick |
||||
*/ |
||||
struct _SDL_Joystick; |
||||
typedef struct _SDL_Joystick SDL_Joystick; |
||||
|
||||
/* A structure that encodes the stable unique id for a joystick device */ |
||||
typedef struct { |
||||
Uint8 data[16]; |
||||
} SDL_JoystickGUID; |
||||
|
||||
/**
|
||||
* This is a unique ID for a joystick for the time it is connected to the system, |
||||
* and is never reused for the lifetime of the application. If the joystick is |
||||
* disconnected and reconnected, it will get a new ID. |
||||
* |
||||
* The ID value starts at 0 and increments from there. The value -1 is an invalid ID. |
||||
*/ |
||||
typedef Sint32 SDL_JoystickID; |
||||
|
||||
typedef enum |
||||
{ |
||||
SDL_JOYSTICK_TYPE_UNKNOWN, |
||||
SDL_JOYSTICK_TYPE_GAMECONTROLLER, |
||||
SDL_JOYSTICK_TYPE_WHEEL, |
||||
SDL_JOYSTICK_TYPE_ARCADE_STICK, |
||||
SDL_JOYSTICK_TYPE_FLIGHT_STICK, |
||||
SDL_JOYSTICK_TYPE_DANCE_PAD, |
||||
SDL_JOYSTICK_TYPE_GUITAR, |
||||
SDL_JOYSTICK_TYPE_DRUM_KIT, |
||||
SDL_JOYSTICK_TYPE_ARCADE_PAD, |
||||
SDL_JOYSTICK_TYPE_THROTTLE |
||||
} SDL_JoystickType; |
||||
|
||||
typedef enum |
||||
{ |
||||
SDL_JOYSTICK_POWER_UNKNOWN = -1, |
||||
SDL_JOYSTICK_POWER_EMPTY, /* <= 5% */ |
||||
SDL_JOYSTICK_POWER_LOW, /* <= 20% */ |
||||
SDL_JOYSTICK_POWER_MEDIUM, /* <= 70% */ |
||||
SDL_JOYSTICK_POWER_FULL, /* <= 100% */ |
||||
SDL_JOYSTICK_POWER_WIRED, |
||||
SDL_JOYSTICK_POWER_MAX |
||||
} SDL_JoystickPowerLevel; |
||||
|
||||
/* Function prototypes */ |
||||
|
||||
/**
|
||||
* Locking for multi-threaded access to the joystick API |
||||
* |
||||
* If you are using the joystick API or handling events from multiple threads |
||||
* you should use these locking functions to protect access to the joysticks. |
||||
* |
||||
* In particular, you are guaranteed that the joystick list won't change, so |
||||
* the API functions that take a joystick index will be valid, and joystick |
||||
* and game controller events will not be delivered. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LockJoysticks(void); |
||||
extern DECLSPEC void SDLCALL SDL_UnlockJoysticks(void); |
||||
|
||||
/**
|
||||
* Count the number of joysticks attached to the system right now |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_NumJoysticks(void); |
||||
|
||||
/**
|
||||
* Get the implementation dependent name of a joystick. |
||||
* This can be called before any joysticks are opened. |
||||
* If no name can be found, this function returns NULL. |
||||
*/ |
||||
extern DECLSPEC const char *SDLCALL SDL_JoystickNameForIndex(int device_index); |
||||
|
||||
/**
|
||||
* Get the player index of a joystick, or -1 if it's not available |
||||
* This can be called before any joysticks are opened. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_JoystickGetDevicePlayerIndex(int device_index); |
||||
|
||||
/**
|
||||
* Return the GUID for the joystick at this index |
||||
* This can be called before any joysticks are opened. |
||||
*/ |
||||
extern DECLSPEC SDL_JoystickGUID SDLCALL SDL_JoystickGetDeviceGUID(int device_index); |
||||
|
||||
/**
|
||||
* Get the USB vendor ID of a joystick, if available. |
||||
* This can be called before any joysticks are opened. |
||||
* If the vendor ID isn't available this function returns 0. |
||||
*/ |
||||
extern DECLSPEC Uint16 SDLCALL SDL_JoystickGetDeviceVendor(int device_index); |
||||
|
||||
/**
|
||||
* Get the USB product ID of a joystick, if available. |
||||
* This can be called before any joysticks are opened. |
||||
* If the product ID isn't available this function returns 0. |
||||
*/ |
||||
extern DECLSPEC Uint16 SDLCALL SDL_JoystickGetDeviceProduct(int device_index); |
||||
|
||||
/**
|
||||
* Get the product version of a joystick, if available. |
||||
* This can be called before any joysticks are opened. |
||||
* If the product version isn't available this function returns 0. |
||||
*/ |
||||
extern DECLSPEC Uint16 SDLCALL SDL_JoystickGetDeviceProductVersion(int device_index); |
||||
|
||||
/**
|
||||
* Get the type of a joystick, if available. |
||||
* This can be called before any joysticks are opened. |
||||
*/ |
||||
extern DECLSPEC SDL_JoystickType SDLCALL SDL_JoystickGetDeviceType(int device_index); |
||||
|
||||
/**
|
||||
* Get the instance ID of a joystick. |
||||
* This can be called before any joysticks are opened. |
||||
* If the index is out of range, this function will return -1. |
||||
*/ |
||||
extern DECLSPEC SDL_JoystickID SDLCALL SDL_JoystickGetDeviceInstanceID(int device_index); |
||||
|
||||
/**
|
||||
* Open a joystick for use. |
||||
* The index passed as an argument refers to the N'th joystick on the system. |
||||
* This index is not the value which will identify this joystick in future |
||||
* joystick events. The joystick's instance id (::SDL_JoystickID) will be used |
||||
* there instead. |
||||
* |
||||
* \return A joystick identifier, or NULL if an error occurred. |
||||
*/ |
||||
extern DECLSPEC SDL_Joystick *SDLCALL SDL_JoystickOpen(int device_index); |
||||
|
||||
/**
|
||||
* Return the SDL_Joystick associated with an instance id. |
||||
*/ |
||||
extern DECLSPEC SDL_Joystick *SDLCALL SDL_JoystickFromInstanceID(SDL_JoystickID joyid); |
||||
|
||||
/**
|
||||
* Return the name for this currently opened joystick. |
||||
* If no name can be found, this function returns NULL. |
||||
*/ |
||||
extern DECLSPEC const char *SDLCALL SDL_JoystickName(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Get the player index of an opened joystick, or -1 if it's not available |
||||
* |
||||
* For XInput controllers this returns the XInput user index. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_JoystickGetPlayerIndex(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Return the GUID for this opened joystick |
||||
*/ |
||||
extern DECLSPEC SDL_JoystickGUID SDLCALL SDL_JoystickGetGUID(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Get the USB vendor ID of an opened joystick, if available. |
||||
* If the vendor ID isn't available this function returns 0. |
||||
*/ |
||||
extern DECLSPEC Uint16 SDLCALL SDL_JoystickGetVendor(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Get the USB product ID of an opened joystick, if available. |
||||
* If the product ID isn't available this function returns 0. |
||||
*/ |
||||
extern DECLSPEC Uint16 SDLCALL SDL_JoystickGetProduct(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Get the product version of an opened joystick, if available. |
||||
* If the product version isn't available this function returns 0. |
||||
*/ |
||||
extern DECLSPEC Uint16 SDLCALL SDL_JoystickGetProductVersion(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Get the type of an opened joystick. |
||||
*/ |
||||
extern DECLSPEC SDL_JoystickType SDLCALL SDL_JoystickGetType(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Return a string representation for this guid. pszGUID must point to at least 33 bytes |
||||
* (32 for the string plus a NULL terminator). |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_JoystickGetGUIDString(SDL_JoystickGUID guid, char *pszGUID, int cbGUID); |
||||
|
||||
/**
|
||||
* Convert a string into a joystick guid |
||||
*/ |
||||
extern DECLSPEC SDL_JoystickGUID SDLCALL SDL_JoystickGetGUIDFromString(const char *pchGUID); |
||||
|
||||
/**
|
||||
* Returns SDL_TRUE if the joystick has been opened and currently connected, or SDL_FALSE if it has not. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_JoystickGetAttached(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Get the instance ID of an opened joystick or -1 if the joystick is invalid. |
||||
*/ |
||||
extern DECLSPEC SDL_JoystickID SDLCALL SDL_JoystickInstanceID(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Get the number of general axis controls on a joystick. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_JoystickNumAxes(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Get the number of trackballs on a joystick. |
||||
* |
||||
* Joystick trackballs have only relative motion events associated |
||||
* with them and their state cannot be polled. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_JoystickNumBalls(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Get the number of POV hats on a joystick. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_JoystickNumHats(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Get the number of buttons on a joystick. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_JoystickNumButtons(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Update the current state of the open joysticks. |
||||
* |
||||
* This is called automatically by the event loop if any joystick |
||||
* events are enabled. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_JoystickUpdate(void); |
||||
|
||||
/**
|
||||
* Enable/disable joystick event polling. |
||||
* |
||||
* If joystick events are disabled, you must call SDL_JoystickUpdate() |
||||
* yourself and check the state of the joystick when you want joystick |
||||
* information. |
||||
* |
||||
* The state can be one of ::SDL_QUERY, ::SDL_ENABLE or ::SDL_IGNORE. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_JoystickEventState(int state); |
||||
|
||||
#define SDL_JOYSTICK_AXIS_MAX 32767 |
||||
#define SDL_JOYSTICK_AXIS_MIN -32768 |
||||
/**
|
||||
* Get the current state of an axis control on a joystick. |
||||
* |
||||
* The state is a value ranging from -32768 to 32767. |
||||
* |
||||
* The axis indices start at index 0. |
||||
*/ |
||||
extern DECLSPEC Sint16 SDLCALL SDL_JoystickGetAxis(SDL_Joystick * joystick, |
||||
int axis); |
||||
|
||||
/**
|
||||
* Get the initial state of an axis control on a joystick. |
||||
* |
||||
* The state is a value ranging from -32768 to 32767. |
||||
* |
||||
* The axis indices start at index 0. |
||||
* |
||||
* \return SDL_TRUE if this axis has any initial value, or SDL_FALSE if not. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_JoystickGetAxisInitialState(SDL_Joystick * joystick, |
||||
int axis, Sint16 *state); |
||||
|
||||
/**
|
||||
* \name Hat positions |
||||
*/ |
||||
/* @{ */ |
||||
#define SDL_HAT_CENTERED 0x00 |
||||
#define SDL_HAT_UP 0x01 |
||||
#define SDL_HAT_RIGHT 0x02 |
||||
#define SDL_HAT_DOWN 0x04 |
||||
#define SDL_HAT_LEFT 0x08 |
||||
#define SDL_HAT_RIGHTUP (SDL_HAT_RIGHT|SDL_HAT_UP) |
||||
#define SDL_HAT_RIGHTDOWN (SDL_HAT_RIGHT|SDL_HAT_DOWN) |
||||
#define SDL_HAT_LEFTUP (SDL_HAT_LEFT|SDL_HAT_UP) |
||||
#define SDL_HAT_LEFTDOWN (SDL_HAT_LEFT|SDL_HAT_DOWN) |
||||
/* @} */ |
||||
|
||||
/**
|
||||
* Get the current state of a POV hat on a joystick. |
||||
* |
||||
* The hat indices start at index 0. |
||||
* |
||||
* \return The return value is one of the following positions: |
||||
* - ::SDL_HAT_CENTERED |
||||
* - ::SDL_HAT_UP |
||||
* - ::SDL_HAT_RIGHT |
||||
* - ::SDL_HAT_DOWN |
||||
* - ::SDL_HAT_LEFT |
||||
* - ::SDL_HAT_RIGHTUP |
||||
* - ::SDL_HAT_RIGHTDOWN |
||||
* - ::SDL_HAT_LEFTUP |
||||
* - ::SDL_HAT_LEFTDOWN |
||||
*/ |
||||
extern DECLSPEC Uint8 SDLCALL SDL_JoystickGetHat(SDL_Joystick * joystick, |
||||
int hat); |
||||
|
||||
/**
|
||||
* Get the ball axis change since the last poll. |
||||
* |
||||
* \return 0, or -1 if you passed it invalid parameters. |
||||
* |
||||
* The ball indices start at index 0. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_JoystickGetBall(SDL_Joystick * joystick, |
||||
int ball, int *dx, int *dy); |
||||
|
||||
/**
|
||||
* Get the current state of a button on a joystick. |
||||
* |
||||
* The button indices start at index 0. |
||||
*/ |
||||
extern DECLSPEC Uint8 SDLCALL SDL_JoystickGetButton(SDL_Joystick * joystick, |
||||
int button); |
||||
|
||||
/**
|
||||
* Trigger a rumble effect |
||||
* Each call to this function cancels any previous rumble effect, and calling it with 0 intensity stops any rumbling. |
||||
* |
||||
* \param joystick The joystick to vibrate |
||||
* \param low_frequency_rumble The intensity of the low frequency (left) rumble motor, from 0 to 0xFFFF |
||||
* \param high_frequency_rumble The intensity of the high frequency (right) rumble motor, from 0 to 0xFFFF |
||||
* \param duration_ms The duration of the rumble effect, in milliseconds |
||||
* |
||||
* \return 0, or -1 if rumble isn't supported on this joystick |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_JoystickRumble(SDL_Joystick * joystick, Uint16 low_frequency_rumble, Uint16 high_frequency_rumble, Uint32 duration_ms); |
||||
|
||||
/**
|
||||
* Close a joystick previously opened with SDL_JoystickOpen(). |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_JoystickClose(SDL_Joystick * joystick); |
||||
|
||||
/**
|
||||
* Return the battery level of this joystick |
||||
*/ |
||||
extern DECLSPEC SDL_JoystickPowerLevel SDLCALL SDL_JoystickCurrentPowerLevel(SDL_Joystick * joystick); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_joystick_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,217 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_keyboard.h |
||||
* |
||||
* Include file for SDL keyboard event handling |
||||
*/ |
||||
|
||||
#ifndef SDL_keyboard_h_ |
||||
#define SDL_keyboard_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
#include "SDL_keycode.h" |
||||
#include "SDL_video.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief The SDL keysym structure, used in key events. |
||||
* |
||||
* \note If you are looking for translated character input, see the ::SDL_TEXTINPUT event. |
||||
*/ |
||||
typedef struct SDL_Keysym |
||||
{ |
||||
SDL_Scancode scancode; /**< SDL physical key code - see ::SDL_Scancode for details */ |
||||
SDL_Keycode sym; /**< SDL virtual key code - see ::SDL_Keycode for details */ |
||||
Uint16 mod; /**< current key modifiers */ |
||||
Uint32 unused; |
||||
} SDL_Keysym; |
||||
|
||||
/* Function prototypes */ |
||||
|
||||
/**
|
||||
* \brief Get the window which currently has keyboard focus. |
||||
*/ |
||||
extern DECLSPEC SDL_Window * SDLCALL SDL_GetKeyboardFocus(void); |
||||
|
||||
/**
|
||||
* \brief Get a snapshot of the current state of the keyboard. |
||||
* |
||||
* \param numkeys if non-NULL, receives the length of the returned array. |
||||
* |
||||
* \return An array of key states. Indexes into this array are obtained by using ::SDL_Scancode values. |
||||
* |
||||
* \b Example: |
||||
* \code |
||||
* const Uint8 *state = SDL_GetKeyboardState(NULL); |
||||
* if ( state[SDL_SCANCODE_RETURN] ) { |
||||
* printf("<RETURN> is pressed.\n"); |
||||
* } |
||||
* \endcode |
||||
*/ |
||||
extern DECLSPEC const Uint8 *SDLCALL SDL_GetKeyboardState(int *numkeys); |
||||
|
||||
/**
|
||||
* \brief Get the current key modifier state for the keyboard. |
||||
*/ |
||||
extern DECLSPEC SDL_Keymod SDLCALL SDL_GetModState(void); |
||||
|
||||
/**
|
||||
* \brief Set the current key modifier state for the keyboard. |
||||
* |
||||
* \note This does not change the keyboard state, only the key modifier flags. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_SetModState(SDL_Keymod modstate); |
||||
|
||||
/**
|
||||
* \brief Get the key code corresponding to the given scancode according |
||||
* to the current keyboard layout. |
||||
* |
||||
* See ::SDL_Keycode for details. |
||||
* |
||||
* \sa SDL_GetKeyName() |
||||
*/ |
||||
extern DECLSPEC SDL_Keycode SDLCALL SDL_GetKeyFromScancode(SDL_Scancode scancode); |
||||
|
||||
/**
|
||||
* \brief Get the scancode corresponding to the given key code according to the |
||||
* current keyboard layout. |
||||
* |
||||
* See ::SDL_Scancode for details. |
||||
* |
||||
* \sa SDL_GetScancodeName() |
||||
*/ |
||||
extern DECLSPEC SDL_Scancode SDLCALL SDL_GetScancodeFromKey(SDL_Keycode key); |
||||
|
||||
/**
|
||||
* \brief Get a human-readable name for a scancode. |
||||
* |
||||
* \return A pointer to the name for the scancode. |
||||
* If the scancode doesn't have a name, this function returns |
||||
* an empty string (""). |
||||
* |
||||
* \sa SDL_Scancode |
||||
*/ |
||||
extern DECLSPEC const char *SDLCALL SDL_GetScancodeName(SDL_Scancode scancode); |
||||
|
||||
/**
|
||||
* \brief Get a scancode from a human-readable name |
||||
* |
||||
* \return scancode, or SDL_SCANCODE_UNKNOWN if the name wasn't recognized |
||||
* |
||||
* \sa SDL_Scancode |
||||
*/ |
||||
extern DECLSPEC SDL_Scancode SDLCALL SDL_GetScancodeFromName(const char *name); |
||||
|
||||
/**
|
||||
* \brief Get a human-readable name for a key. |
||||
* |
||||
* \return A pointer to a UTF-8 string that stays valid at least until the next |
||||
* call to this function. If you need it around any longer, you must |
||||
* copy it. If the key doesn't have a name, this function returns an |
||||
* empty string (""). |
||||
* |
||||
* \sa SDL_Keycode |
||||
*/ |
||||
extern DECLSPEC const char *SDLCALL SDL_GetKeyName(SDL_Keycode key); |
||||
|
||||
/**
|
||||
* \brief Get a key code from a human-readable name |
||||
* |
||||
* \return key code, or SDLK_UNKNOWN if the name wasn't recognized |
||||
* |
||||
* \sa SDL_Keycode |
||||
*/ |
||||
extern DECLSPEC SDL_Keycode SDLCALL SDL_GetKeyFromName(const char *name); |
||||
|
||||
/**
|
||||
* \brief Start accepting Unicode text input events. |
||||
* This function will show the on-screen keyboard if supported. |
||||
* |
||||
* \sa SDL_StopTextInput() |
||||
* \sa SDL_SetTextInputRect() |
||||
* \sa SDL_HasScreenKeyboardSupport() |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_StartTextInput(void); |
||||
|
||||
/**
|
||||
* \brief Return whether or not Unicode text input events are enabled. |
||||
* |
||||
* \sa SDL_StartTextInput() |
||||
* \sa SDL_StopTextInput() |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_IsTextInputActive(void); |
||||
|
||||
/**
|
||||
* \brief Stop receiving any text input events. |
||||
* This function will hide the on-screen keyboard if supported. |
||||
* |
||||
* \sa SDL_StartTextInput() |
||||
* \sa SDL_HasScreenKeyboardSupport() |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_StopTextInput(void); |
||||
|
||||
/**
|
||||
* \brief Set the rectangle used to type Unicode text inputs. |
||||
* This is used as a hint for IME and on-screen keyboard placement. |
||||
* |
||||
* \sa SDL_StartTextInput() |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_SetTextInputRect(SDL_Rect *rect); |
||||
|
||||
/**
|
||||
* \brief Returns whether the platform has some screen keyboard support. |
||||
* |
||||
* \return SDL_TRUE if some keyboard support is available else SDL_FALSE. |
||||
* |
||||
* \note Not all screen keyboard functions are supported on all platforms. |
||||
* |
||||
* \sa SDL_IsScreenKeyboardShown() |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasScreenKeyboardSupport(void); |
||||
|
||||
/**
|
||||
* \brief Returns whether the screen keyboard is shown for given window. |
||||
* |
||||
* \param window The window for which screen keyboard should be queried. |
||||
* |
||||
* \return SDL_TRUE if screen keyboard is shown else SDL_FALSE. |
||||
* |
||||
* \sa SDL_HasScreenKeyboardSupport() |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_IsScreenKeyboardShown(SDL_Window *window); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_keyboard_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,349 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_keycode.h |
||||
* |
||||
* Defines constants which identify keyboard keys and modifiers. |
||||
*/ |
||||
|
||||
#ifndef SDL_keycode_h_ |
||||
#define SDL_keycode_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_scancode.h" |
||||
|
||||
/**
|
||||
* \brief The SDL virtual key representation. |
||||
* |
||||
* Values of this type are used to represent keyboard keys using the current |
||||
* layout of the keyboard. These values include Unicode values representing |
||||
* the unmodified character that would be generated by pressing the key, or |
||||
* an SDLK_* constant for those keys that do not generate characters. |
||||
* |
||||
* A special exception is the number keys at the top of the keyboard which |
||||
* always map to SDLK_0...SDLK_9, regardless of layout. |
||||
*/ |
||||
typedef Sint32 SDL_Keycode; |
||||
|
||||
#define SDLK_SCANCODE_MASK (1<<30) |
||||
#define SDL_SCANCODE_TO_KEYCODE(X) (X | SDLK_SCANCODE_MASK) |
||||
|
||||
enum |
||||
{ |
||||
SDLK_UNKNOWN = 0, |
||||
|
||||
SDLK_RETURN = '\r', |
||||
SDLK_ESCAPE = '\033', |
||||
SDLK_BACKSPACE = '\b', |
||||
SDLK_TAB = '\t', |
||||
SDLK_SPACE = ' ', |
||||
SDLK_EXCLAIM = '!', |
||||
SDLK_QUOTEDBL = '"', |
||||
SDLK_HASH = '#', |
||||
SDLK_PERCENT = '%', |
||||
SDLK_DOLLAR = '$', |
||||
SDLK_AMPERSAND = '&', |
||||
SDLK_QUOTE = '\'', |
||||
SDLK_LEFTPAREN = '(', |
||||
SDLK_RIGHTPAREN = ')', |
||||
SDLK_ASTERISK = '*', |
||||
SDLK_PLUS = '+', |
||||
SDLK_COMMA = ',', |
||||
SDLK_MINUS = '-', |
||||
SDLK_PERIOD = '.', |
||||
SDLK_SLASH = '/', |
||||
SDLK_0 = '0', |
||||
SDLK_1 = '1', |
||||
SDLK_2 = '2', |
||||
SDLK_3 = '3', |
||||
SDLK_4 = '4', |
||||
SDLK_5 = '5', |
||||
SDLK_6 = '6', |
||||
SDLK_7 = '7', |
||||
SDLK_8 = '8', |
||||
SDLK_9 = '9', |
||||
SDLK_COLON = ':', |
||||
SDLK_SEMICOLON = ';', |
||||
SDLK_LESS = '<', |
||||
SDLK_EQUALS = '=', |
||||
SDLK_GREATER = '>', |
||||
SDLK_QUESTION = '?', |
||||
SDLK_AT = '@', |
||||
/*
|
||||
Skip uppercase letters |
||||
*/ |
||||
SDLK_LEFTBRACKET = '[', |
||||
SDLK_BACKSLASH = '\\', |
||||
SDLK_RIGHTBRACKET = ']', |
||||
SDLK_CARET = '^', |
||||
SDLK_UNDERSCORE = '_', |
||||
SDLK_BACKQUOTE = '`', |
||||
SDLK_a = 'a', |
||||
SDLK_b = 'b', |
||||
SDLK_c = 'c', |
||||
SDLK_d = 'd', |
||||
SDLK_e = 'e', |
||||
SDLK_f = 'f', |
||||
SDLK_g = 'g', |
||||
SDLK_h = 'h', |
||||
SDLK_i = 'i', |
||||
SDLK_j = 'j', |
||||
SDLK_k = 'k', |
||||
SDLK_l = 'l', |
||||
SDLK_m = 'm', |
||||
SDLK_n = 'n', |
||||
SDLK_o = 'o', |
||||
SDLK_p = 'p', |
||||
SDLK_q = 'q', |
||||
SDLK_r = 'r', |
||||
SDLK_s = 's', |
||||
SDLK_t = 't', |
||||
SDLK_u = 'u', |
||||
SDLK_v = 'v', |
||||
SDLK_w = 'w', |
||||
SDLK_x = 'x', |
||||
SDLK_y = 'y', |
||||
SDLK_z = 'z', |
||||
|
||||
SDLK_CAPSLOCK = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_CAPSLOCK), |
||||
|
||||
SDLK_F1 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F1), |
||||
SDLK_F2 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F2), |
||||
SDLK_F3 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F3), |
||||
SDLK_F4 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F4), |
||||
SDLK_F5 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F5), |
||||
SDLK_F6 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F6), |
||||
SDLK_F7 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F7), |
||||
SDLK_F8 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F8), |
||||
SDLK_F9 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F9), |
||||
SDLK_F10 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F10), |
||||
SDLK_F11 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F11), |
||||
SDLK_F12 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F12), |
||||
|
||||
SDLK_PRINTSCREEN = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_PRINTSCREEN), |
||||
SDLK_SCROLLLOCK = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_SCROLLLOCK), |
||||
SDLK_PAUSE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_PAUSE), |
||||
SDLK_INSERT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_INSERT), |
||||
SDLK_HOME = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_HOME), |
||||
SDLK_PAGEUP = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_PAGEUP), |
||||
SDLK_DELETE = '\177', |
||||
SDLK_END = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_END), |
||||
SDLK_PAGEDOWN = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_PAGEDOWN), |
||||
SDLK_RIGHT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_RIGHT), |
||||
SDLK_LEFT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_LEFT), |
||||
SDLK_DOWN = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_DOWN), |
||||
SDLK_UP = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_UP), |
||||
|
||||
SDLK_NUMLOCKCLEAR = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_NUMLOCKCLEAR), |
||||
SDLK_KP_DIVIDE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_DIVIDE), |
||||
SDLK_KP_MULTIPLY = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_MULTIPLY), |
||||
SDLK_KP_MINUS = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_MINUS), |
||||
SDLK_KP_PLUS = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_PLUS), |
||||
SDLK_KP_ENTER = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_ENTER), |
||||
SDLK_KP_1 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_1), |
||||
SDLK_KP_2 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_2), |
||||
SDLK_KP_3 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_3), |
||||
SDLK_KP_4 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_4), |
||||
SDLK_KP_5 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_5), |
||||
SDLK_KP_6 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_6), |
||||
SDLK_KP_7 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_7), |
||||
SDLK_KP_8 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_8), |
||||
SDLK_KP_9 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_9), |
||||
SDLK_KP_0 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_0), |
||||
SDLK_KP_PERIOD = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_PERIOD), |
||||
|
||||
SDLK_APPLICATION = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_APPLICATION), |
||||
SDLK_POWER = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_POWER), |
||||
SDLK_KP_EQUALS = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_EQUALS), |
||||
SDLK_F13 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F13), |
||||
SDLK_F14 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F14), |
||||
SDLK_F15 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F15), |
||||
SDLK_F16 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F16), |
||||
SDLK_F17 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F17), |
||||
SDLK_F18 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F18), |
||||
SDLK_F19 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F19), |
||||
SDLK_F20 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F20), |
||||
SDLK_F21 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F21), |
||||
SDLK_F22 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F22), |
||||
SDLK_F23 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F23), |
||||
SDLK_F24 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_F24), |
||||
SDLK_EXECUTE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_EXECUTE), |
||||
SDLK_HELP = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_HELP), |
||||
SDLK_MENU = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_MENU), |
||||
SDLK_SELECT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_SELECT), |
||||
SDLK_STOP = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_STOP), |
||||
SDLK_AGAIN = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AGAIN), |
||||
SDLK_UNDO = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_UNDO), |
||||
SDLK_CUT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_CUT), |
||||
SDLK_COPY = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_COPY), |
||||
SDLK_PASTE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_PASTE), |
||||
SDLK_FIND = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_FIND), |
||||
SDLK_MUTE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_MUTE), |
||||
SDLK_VOLUMEUP = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_VOLUMEUP), |
||||
SDLK_VOLUMEDOWN = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_VOLUMEDOWN), |
||||
SDLK_KP_COMMA = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_COMMA), |
||||
SDLK_KP_EQUALSAS400 = |
||||
SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_EQUALSAS400), |
||||
|
||||
SDLK_ALTERASE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_ALTERASE), |
||||
SDLK_SYSREQ = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_SYSREQ), |
||||
SDLK_CANCEL = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_CANCEL), |
||||
SDLK_CLEAR = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_CLEAR), |
||||
SDLK_PRIOR = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_PRIOR), |
||||
SDLK_RETURN2 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_RETURN2), |
||||
SDLK_SEPARATOR = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_SEPARATOR), |
||||
SDLK_OUT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_OUT), |
||||
SDLK_OPER = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_OPER), |
||||
SDLK_CLEARAGAIN = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_CLEARAGAIN), |
||||
SDLK_CRSEL = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_CRSEL), |
||||
SDLK_EXSEL = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_EXSEL), |
||||
|
||||
SDLK_KP_00 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_00), |
||||
SDLK_KP_000 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_000), |
||||
SDLK_THOUSANDSSEPARATOR = |
||||
SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_THOUSANDSSEPARATOR), |
||||
SDLK_DECIMALSEPARATOR = |
||||
SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_DECIMALSEPARATOR), |
||||
SDLK_CURRENCYUNIT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_CURRENCYUNIT), |
||||
SDLK_CURRENCYSUBUNIT = |
||||
SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_CURRENCYSUBUNIT), |
||||
SDLK_KP_LEFTPAREN = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_LEFTPAREN), |
||||
SDLK_KP_RIGHTPAREN = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_RIGHTPAREN), |
||||
SDLK_KP_LEFTBRACE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_LEFTBRACE), |
||||
SDLK_KP_RIGHTBRACE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_RIGHTBRACE), |
||||
SDLK_KP_TAB = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_TAB), |
||||
SDLK_KP_BACKSPACE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_BACKSPACE), |
||||
SDLK_KP_A = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_A), |
||||
SDLK_KP_B = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_B), |
||||
SDLK_KP_C = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_C), |
||||
SDLK_KP_D = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_D), |
||||
SDLK_KP_E = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_E), |
||||
SDLK_KP_F = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_F), |
||||
SDLK_KP_XOR = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_XOR), |
||||
SDLK_KP_POWER = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_POWER), |
||||
SDLK_KP_PERCENT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_PERCENT), |
||||
SDLK_KP_LESS = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_LESS), |
||||
SDLK_KP_GREATER = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_GREATER), |
||||
SDLK_KP_AMPERSAND = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_AMPERSAND), |
||||
SDLK_KP_DBLAMPERSAND = |
||||
SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_DBLAMPERSAND), |
||||
SDLK_KP_VERTICALBAR = |
||||
SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_VERTICALBAR), |
||||
SDLK_KP_DBLVERTICALBAR = |
||||
SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_DBLVERTICALBAR), |
||||
SDLK_KP_COLON = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_COLON), |
||||
SDLK_KP_HASH = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_HASH), |
||||
SDLK_KP_SPACE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_SPACE), |
||||
SDLK_KP_AT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_AT), |
||||
SDLK_KP_EXCLAM = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_EXCLAM), |
||||
SDLK_KP_MEMSTORE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_MEMSTORE), |
||||
SDLK_KP_MEMRECALL = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_MEMRECALL), |
||||
SDLK_KP_MEMCLEAR = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_MEMCLEAR), |
||||
SDLK_KP_MEMADD = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_MEMADD), |
||||
SDLK_KP_MEMSUBTRACT = |
||||
SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_MEMSUBTRACT), |
||||
SDLK_KP_MEMMULTIPLY = |
||||
SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_MEMMULTIPLY), |
||||
SDLK_KP_MEMDIVIDE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_MEMDIVIDE), |
||||
SDLK_KP_PLUSMINUS = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_PLUSMINUS), |
||||
SDLK_KP_CLEAR = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_CLEAR), |
||||
SDLK_KP_CLEARENTRY = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_CLEARENTRY), |
||||
SDLK_KP_BINARY = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_BINARY), |
||||
SDLK_KP_OCTAL = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_OCTAL), |
||||
SDLK_KP_DECIMAL = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_DECIMAL), |
||||
SDLK_KP_HEXADECIMAL = |
||||
SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KP_HEXADECIMAL), |
||||
|
||||
SDLK_LCTRL = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_LCTRL), |
||||
SDLK_LSHIFT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_LSHIFT), |
||||
SDLK_LALT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_LALT), |
||||
SDLK_LGUI = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_LGUI), |
||||
SDLK_RCTRL = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_RCTRL), |
||||
SDLK_RSHIFT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_RSHIFT), |
||||
SDLK_RALT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_RALT), |
||||
SDLK_RGUI = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_RGUI), |
||||
|
||||
SDLK_MODE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_MODE), |
||||
|
||||
SDLK_AUDIONEXT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AUDIONEXT), |
||||
SDLK_AUDIOPREV = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AUDIOPREV), |
||||
SDLK_AUDIOSTOP = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AUDIOSTOP), |
||||
SDLK_AUDIOPLAY = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AUDIOPLAY), |
||||
SDLK_AUDIOMUTE = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AUDIOMUTE), |
||||
SDLK_MEDIASELECT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_MEDIASELECT), |
||||
SDLK_WWW = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_WWW), |
||||
SDLK_MAIL = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_MAIL), |
||||
SDLK_CALCULATOR = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_CALCULATOR), |
||||
SDLK_COMPUTER = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_COMPUTER), |
||||
SDLK_AC_SEARCH = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AC_SEARCH), |
||||
SDLK_AC_HOME = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AC_HOME), |
||||
SDLK_AC_BACK = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AC_BACK), |
||||
SDLK_AC_FORWARD = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AC_FORWARD), |
||||
SDLK_AC_STOP = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AC_STOP), |
||||
SDLK_AC_REFRESH = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AC_REFRESH), |
||||
SDLK_AC_BOOKMARKS = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AC_BOOKMARKS), |
||||
|
||||
SDLK_BRIGHTNESSDOWN = |
||||
SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_BRIGHTNESSDOWN), |
||||
SDLK_BRIGHTNESSUP = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_BRIGHTNESSUP), |
||||
SDLK_DISPLAYSWITCH = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_DISPLAYSWITCH), |
||||
SDLK_KBDILLUMTOGGLE = |
||||
SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KBDILLUMTOGGLE), |
||||
SDLK_KBDILLUMDOWN = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KBDILLUMDOWN), |
||||
SDLK_KBDILLUMUP = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_KBDILLUMUP), |
||||
SDLK_EJECT = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_EJECT), |
||||
SDLK_SLEEP = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_SLEEP), |
||||
SDLK_APP1 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_APP1), |
||||
SDLK_APP2 = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_APP2), |
||||
|
||||
SDLK_AUDIOREWIND = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AUDIOREWIND), |
||||
SDLK_AUDIOFASTFORWARD = SDL_SCANCODE_TO_KEYCODE(SDL_SCANCODE_AUDIOFASTFORWARD) |
||||
}; |
||||
|
||||
/**
|
||||
* \brief Enumeration of valid key mods (possibly OR'd together). |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
KMOD_NONE = 0x0000, |
||||
KMOD_LSHIFT = 0x0001, |
||||
KMOD_RSHIFT = 0x0002, |
||||
KMOD_LCTRL = 0x0040, |
||||
KMOD_RCTRL = 0x0080, |
||||
KMOD_LALT = 0x0100, |
||||
KMOD_RALT = 0x0200, |
||||
KMOD_LGUI = 0x0400, |
||||
KMOD_RGUI = 0x0800, |
||||
KMOD_NUM = 0x1000, |
||||
KMOD_CAPS = 0x2000, |
||||
KMOD_MODE = 0x4000, |
||||
KMOD_RESERVED = 0x8000 |
||||
} SDL_Keymod; |
||||
|
||||
#define KMOD_CTRL (KMOD_LCTRL|KMOD_RCTRL) |
||||
#define KMOD_SHIFT (KMOD_LSHIFT|KMOD_RSHIFT) |
||||
#define KMOD_ALT (KMOD_LALT|KMOD_RALT) |
||||
#define KMOD_GUI (KMOD_LGUI|KMOD_RGUI) |
||||
|
||||
#endif /* SDL_keycode_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,81 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_loadso.h |
||||
* |
||||
* System dependent library loading routines |
||||
* |
||||
* Some things to keep in mind: |
||||
* \li These functions only work on C function names. Other languages may |
||||
* have name mangling and intrinsic language support that varies from |
||||
* compiler to compiler. |
||||
* \li Make sure you declare your function pointers with the same calling |
||||
* convention as the actual library function. Your code will crash |
||||
* mysteriously if you do not do this. |
||||
* \li Avoid namespace collisions. If you load a symbol from the library, |
||||
* it is not defined whether or not it goes into the global symbol |
||||
* namespace for the application. If it does and it conflicts with |
||||
* symbols in your code or other shared libraries, you will not get |
||||
* the results you expect. :) |
||||
*/ |
||||
|
||||
#ifndef SDL_loadso_h_ |
||||
#define SDL_loadso_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* This function dynamically loads a shared object and returns a pointer |
||||
* to the object handle (or NULL if there was an error). |
||||
* The 'sofile' parameter is a system dependent name of the object file. |
||||
*/ |
||||
extern DECLSPEC void *SDLCALL SDL_LoadObject(const char *sofile); |
||||
|
||||
/**
|
||||
* Given an object handle, this function looks up the address of the |
||||
* named function in the shared object and returns it. This address |
||||
* is no longer valid after calling SDL_UnloadObject(). |
||||
*/ |
||||
extern DECLSPEC void *SDLCALL SDL_LoadFunction(void *handle, |
||||
const char *name); |
||||
|
||||
/**
|
||||
* Unload a shared object from memory. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_UnloadObject(void *handle); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_loadso_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,211 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_log.h |
||||
* |
||||
* Simple log messages with categories and priorities. |
||||
* |
||||
* By default logs are quiet, but if you're debugging SDL you might want: |
||||
* |
||||
* SDL_LogSetAllPriority(SDL_LOG_PRIORITY_WARN); |
||||
* |
||||
* Here's where the messages go on different platforms: |
||||
* Windows: debug output stream |
||||
* Android: log output |
||||
* Others: standard error output (stderr) |
||||
*/ |
||||
|
||||
#ifndef SDL_log_h_ |
||||
#define SDL_log_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
/**
|
||||
* \brief The maximum size of a log message |
||||
* |
||||
* Messages longer than the maximum size will be truncated |
||||
*/ |
||||
#define SDL_MAX_LOG_MESSAGE 4096 |
||||
|
||||
/**
|
||||
* \brief The predefined log categories |
||||
* |
||||
* By default the application category is enabled at the INFO level, |
||||
* the assert category is enabled at the WARN level, test is enabled |
||||
* at the VERBOSE level and all other categories are enabled at the |
||||
* CRITICAL level. |
||||
*/ |
||||
enum |
||||
{ |
||||
SDL_LOG_CATEGORY_APPLICATION, |
||||
SDL_LOG_CATEGORY_ERROR, |
||||
SDL_LOG_CATEGORY_ASSERT, |
||||
SDL_LOG_CATEGORY_SYSTEM, |
||||
SDL_LOG_CATEGORY_AUDIO, |
||||
SDL_LOG_CATEGORY_VIDEO, |
||||
SDL_LOG_CATEGORY_RENDER, |
||||
SDL_LOG_CATEGORY_INPUT, |
||||
SDL_LOG_CATEGORY_TEST, |
||||
|
||||
/* Reserved for future SDL library use */ |
||||
SDL_LOG_CATEGORY_RESERVED1, |
||||
SDL_LOG_CATEGORY_RESERVED2, |
||||
SDL_LOG_CATEGORY_RESERVED3, |
||||
SDL_LOG_CATEGORY_RESERVED4, |
||||
SDL_LOG_CATEGORY_RESERVED5, |
||||
SDL_LOG_CATEGORY_RESERVED6, |
||||
SDL_LOG_CATEGORY_RESERVED7, |
||||
SDL_LOG_CATEGORY_RESERVED8, |
||||
SDL_LOG_CATEGORY_RESERVED9, |
||||
SDL_LOG_CATEGORY_RESERVED10, |
||||
|
||||
/* Beyond this point is reserved for application use, e.g.
|
||||
enum { |
||||
MYAPP_CATEGORY_AWESOME1 = SDL_LOG_CATEGORY_CUSTOM, |
||||
MYAPP_CATEGORY_AWESOME2, |
||||
MYAPP_CATEGORY_AWESOME3, |
||||
... |
||||
}; |
||||
*/ |
||||
SDL_LOG_CATEGORY_CUSTOM |
||||
}; |
||||
|
||||
/**
|
||||
* \brief The predefined log priorities |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_LOG_PRIORITY_VERBOSE = 1, |
||||
SDL_LOG_PRIORITY_DEBUG, |
||||
SDL_LOG_PRIORITY_INFO, |
||||
SDL_LOG_PRIORITY_WARN, |
||||
SDL_LOG_PRIORITY_ERROR, |
||||
SDL_LOG_PRIORITY_CRITICAL, |
||||
SDL_NUM_LOG_PRIORITIES |
||||
} SDL_LogPriority; |
||||
|
||||
|
||||
/**
|
||||
* \brief Set the priority of all log categories |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogSetAllPriority(SDL_LogPriority priority); |
||||
|
||||
/**
|
||||
* \brief Set the priority of a particular log category |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogSetPriority(int category, |
||||
SDL_LogPriority priority); |
||||
|
||||
/**
|
||||
* \brief Get the priority of a particular log category |
||||
*/ |
||||
extern DECLSPEC SDL_LogPriority SDLCALL SDL_LogGetPriority(int category); |
||||
|
||||
/**
|
||||
* \brief Reset all priorities to default. |
||||
* |
||||
* \note This is called in SDL_Quit(). |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogResetPriorities(void); |
||||
|
||||
/**
|
||||
* \brief Log a message with SDL_LOG_CATEGORY_APPLICATION and SDL_LOG_PRIORITY_INFO |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_Log(SDL_PRINTF_FORMAT_STRING const char *fmt, ...) SDL_PRINTF_VARARG_FUNC(1); |
||||
|
||||
/**
|
||||
* \brief Log a message with SDL_LOG_PRIORITY_VERBOSE |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogVerbose(int category, SDL_PRINTF_FORMAT_STRING const char *fmt, ...) SDL_PRINTF_VARARG_FUNC(2); |
||||
|
||||
/**
|
||||
* \brief Log a message with SDL_LOG_PRIORITY_DEBUG |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogDebug(int category, SDL_PRINTF_FORMAT_STRING const char *fmt, ...) SDL_PRINTF_VARARG_FUNC(2); |
||||
|
||||
/**
|
||||
* \brief Log a message with SDL_LOG_PRIORITY_INFO |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogInfo(int category, SDL_PRINTF_FORMAT_STRING const char *fmt, ...) SDL_PRINTF_VARARG_FUNC(2); |
||||
|
||||
/**
|
||||
* \brief Log a message with SDL_LOG_PRIORITY_WARN |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogWarn(int category, SDL_PRINTF_FORMAT_STRING const char *fmt, ...) SDL_PRINTF_VARARG_FUNC(2); |
||||
|
||||
/**
|
||||
* \brief Log a message with SDL_LOG_PRIORITY_ERROR |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogError(int category, SDL_PRINTF_FORMAT_STRING const char *fmt, ...) SDL_PRINTF_VARARG_FUNC(2); |
||||
|
||||
/**
|
||||
* \brief Log a message with SDL_LOG_PRIORITY_CRITICAL |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogCritical(int category, SDL_PRINTF_FORMAT_STRING const char *fmt, ...) SDL_PRINTF_VARARG_FUNC(2); |
||||
|
||||
/**
|
||||
* \brief Log a message with the specified category and priority. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogMessage(int category, |
||||
SDL_LogPriority priority, |
||||
SDL_PRINTF_FORMAT_STRING const char *fmt, ...) SDL_PRINTF_VARARG_FUNC(3); |
||||
|
||||
/**
|
||||
* \brief Log a message with the specified category and priority. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogMessageV(int category, |
||||
SDL_LogPriority priority, |
||||
const char *fmt, va_list ap); |
||||
|
||||
/**
|
||||
* \brief The prototype for the log output function |
||||
*/ |
||||
typedef void (SDLCALL *SDL_LogOutputFunction)(void *userdata, int category, SDL_LogPriority priority, const char *message); |
||||
|
||||
/**
|
||||
* \brief Get the current log output function. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogGetOutputFunction(SDL_LogOutputFunction *callback, void **userdata); |
||||
|
||||
/**
|
||||
* \brief This function allows you to replace the default log output |
||||
* function with one of your own. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_LogSetOutputFunction(SDL_LogOutputFunction callback, void *userdata); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_log_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,180 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
#ifndef SDL_main_h_ |
||||
#define SDL_main_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
|
||||
/**
|
||||
* \file SDL_main.h |
||||
* |
||||
* Redefine main() on some platforms so that it is called by SDL. |
||||
*/ |
||||
|
||||
#ifndef SDL_MAIN_HANDLED |
||||
#if defined(__WIN32__) |
||||
/* On Windows SDL provides WinMain(), which parses the command line and passes
|
||||
the arguments to your main function. |
||||
|
||||
If you provide your own WinMain(), you may define SDL_MAIN_HANDLED |
||||
*/ |
||||
#define SDL_MAIN_AVAILABLE |
||||
|
||||
#elif defined(__WINRT__) |
||||
/* On WinRT, SDL provides a main function that initializes CoreApplication,
|
||||
creating an instance of IFrameworkView in the process. |
||||
|
||||
Please note that #include'ing SDL_main.h is not enough to get a main() |
||||
function working. In non-XAML apps, the file, |
||||
src/main/winrt/SDL_WinRT_main_NonXAML.cpp, or a copy of it, must be compiled |
||||
into the app itself. In XAML apps, the function, SDL_WinRTRunApp must be |
||||
called, with a pointer to the Direct3D-hosted XAML control passed in. |
||||
*/ |
||||
#define SDL_MAIN_NEEDED |
||||
|
||||
#elif defined(__IPHONEOS__) |
||||
/* On iOS SDL provides a main function that creates an application delegate
|
||||
and starts the iOS application run loop. |
||||
|
||||
If you link with SDL dynamically on iOS, the main function can't be in a |
||||
shared library, so you need to link with libSDLmain.a, which includes a |
||||
stub main function that calls into the shared library to start execution. |
||||
|
||||
See src/video/uikit/SDL_uikitappdelegate.m for more details. |
||||
*/ |
||||
#define SDL_MAIN_NEEDED |
||||
|
||||
#elif defined(__ANDROID__) |
||||
/* On Android SDL provides a Java class in SDLActivity.java that is the
|
||||
main activity entry point. |
||||
|
||||
See docs/README-android.md for more details on extending that class. |
||||
*/ |
||||
#define SDL_MAIN_NEEDED |
||||
|
||||
/* We need to export SDL_main so it can be launched from Java */ |
||||
#define SDLMAIN_DECLSPEC DECLSPEC |
||||
|
||||
#elif defined(__NACL__) |
||||
/* On NACL we use ppapi_simple to set up the application helper code,
|
||||
then wait for the first PSE_INSTANCE_DIDCHANGEVIEW event before
|
||||
starting the user main function. |
||||
All user code is run in a separate thread by ppapi_simple, thus
|
||||
allowing for blocking io to take place via nacl_io |
||||
*/ |
||||
#define SDL_MAIN_NEEDED |
||||
|
||||
#endif |
||||
#endif /* SDL_MAIN_HANDLED */ |
||||
|
||||
#ifndef SDLMAIN_DECLSPEC |
||||
#define SDLMAIN_DECLSPEC |
||||
#endif |
||||
|
||||
/**
|
||||
* \file SDL_main.h |
||||
* |
||||
* The application's main() function must be called with C linkage, |
||||
* and should be declared like this: |
||||
* \code |
||||
* #ifdef __cplusplus |
||||
* extern "C" |
||||
* #endif |
||||
* int main(int argc, char *argv[]) |
||||
* { |
||||
* } |
||||
* \endcode |
||||
*/ |
||||
|
||||
#if defined(SDL_MAIN_NEEDED) || defined(SDL_MAIN_AVAILABLE) |
||||
#define main SDL_main |
||||
#endif |
||||
|
||||
#include "begin_code.h" |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* The prototype for the application's main() function |
||||
*/ |
||||
typedef int (*SDL_main_func)(int argc, char *argv[]); |
||||
extern SDLMAIN_DECLSPEC int SDL_main(int argc, char *argv[]); |
||||
|
||||
|
||||
/**
|
||||
* This is called by the real SDL main function to let the rest of the |
||||
* library know that initialization was done properly. |
||||
* |
||||
* Calling this yourself without knowing what you're doing can cause |
||||
* crashes and hard to diagnose problems with your application. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_SetMainReady(void); |
||||
|
||||
#ifdef __WIN32__ |
||||
|
||||
/**
|
||||
* This can be called to set the application class at startup |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_RegisterApp(char *name, Uint32 style, void *hInst); |
||||
extern DECLSPEC void SDLCALL SDL_UnregisterApp(void); |
||||
|
||||
#endif /* __WIN32__ */ |
||||
|
||||
|
||||
#ifdef __WINRT__ |
||||
|
||||
/**
|
||||
* \brief Initializes and launches an SDL/WinRT application. |
||||
* |
||||
* \param mainFunction The SDL app's C-style main(). |
||||
* \param reserved Reserved for future use; should be NULL |
||||
* \return 0 on success, -1 on failure. On failure, use SDL_GetError to retrieve more |
||||
* information on the failure. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_WinRTRunApp(SDL_main_func mainFunction, void * reserved); |
||||
|
||||
#endif /* __WINRT__ */ |
||||
|
||||
#if defined(__IPHONEOS__) |
||||
|
||||
/**
|
||||
* \brief Initializes and launches an SDL application. |
||||
* |
||||
* \param argc The argc parameter from the application's main() function |
||||
* \param argv The argv parameter from the application's main() function |
||||
* \param mainFunction The SDL app's C-style main(). |
||||
* \return the return value from mainFunction |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_UIKitRunApp(int argc, char *argv[], SDL_main_func mainFunction); |
||||
|
||||
#endif /* __IPHONEOS__ */ |
||||
|
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_main_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,144 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
#ifndef SDL_messagebox_h_ |
||||
#define SDL_messagebox_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_video.h" /* For SDL_Window */ |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief SDL_MessageBox flags. If supported will display warning icon, etc. |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_MESSAGEBOX_ERROR = 0x00000010, /**< error dialog */ |
||||
SDL_MESSAGEBOX_WARNING = 0x00000020, /**< warning dialog */ |
||||
SDL_MESSAGEBOX_INFORMATION = 0x00000040 /**< informational dialog */ |
||||
} SDL_MessageBoxFlags; |
||||
|
||||
/**
|
||||
* \brief Flags for SDL_MessageBoxButtonData. |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_MESSAGEBOX_BUTTON_RETURNKEY_DEFAULT = 0x00000001, /**< Marks the default button when return is hit */ |
||||
SDL_MESSAGEBOX_BUTTON_ESCAPEKEY_DEFAULT = 0x00000002 /**< Marks the default button when escape is hit */ |
||||
} SDL_MessageBoxButtonFlags; |
||||
|
||||
/**
|
||||
* \brief Individual button data. |
||||
*/ |
||||
typedef struct |
||||
{ |
||||
Uint32 flags; /**< ::SDL_MessageBoxButtonFlags */ |
||||
int buttonid; /**< User defined button id (value returned via SDL_ShowMessageBox) */ |
||||
const char * text; /**< The UTF-8 button text */ |
||||
} SDL_MessageBoxButtonData; |
||||
|
||||
/**
|
||||
* \brief RGB value used in a message box color scheme |
||||
*/ |
||||
typedef struct |
||||
{ |
||||
Uint8 r, g, b; |
||||
} SDL_MessageBoxColor; |
||||
|
||||
typedef enum |
||||
{ |
||||
SDL_MESSAGEBOX_COLOR_BACKGROUND, |
||||
SDL_MESSAGEBOX_COLOR_TEXT, |
||||
SDL_MESSAGEBOX_COLOR_BUTTON_BORDER, |
||||
SDL_MESSAGEBOX_COLOR_BUTTON_BACKGROUND, |
||||
SDL_MESSAGEBOX_COLOR_BUTTON_SELECTED, |
||||
SDL_MESSAGEBOX_COLOR_MAX |
||||
} SDL_MessageBoxColorType; |
||||
|
||||
/**
|
||||
* \brief A set of colors to use for message box dialogs |
||||
*/ |
||||
typedef struct |
||||
{ |
||||
SDL_MessageBoxColor colors[SDL_MESSAGEBOX_COLOR_MAX]; |
||||
} SDL_MessageBoxColorScheme; |
||||
|
||||
/**
|
||||
* \brief MessageBox structure containing title, text, window, etc. |
||||
*/ |
||||
typedef struct |
||||
{ |
||||
Uint32 flags; /**< ::SDL_MessageBoxFlags */ |
||||
SDL_Window *window; /**< Parent window, can be NULL */ |
||||
const char *title; /**< UTF-8 title */ |
||||
const char *message; /**< UTF-8 message text */ |
||||
|
||||
int numbuttons; |
||||
const SDL_MessageBoxButtonData *buttons; |
||||
|
||||
const SDL_MessageBoxColorScheme *colorScheme; /**< ::SDL_MessageBoxColorScheme, can be NULL to use system settings */ |
||||
} SDL_MessageBoxData; |
||||
|
||||
/**
|
||||
* \brief Create a modal message box. |
||||
* |
||||
* \param messageboxdata The SDL_MessageBoxData structure with title, text, etc. |
||||
* \param buttonid The pointer to which user id of hit button should be copied. |
||||
* |
||||
* \return -1 on error, otherwise 0 and buttonid contains user id of button |
||||
* hit or -1 if dialog was closed. |
||||
* |
||||
* \note This function should be called on the thread that created the parent |
||||
* window, or on the main thread if the messagebox has no parent. It will |
||||
* block execution of that thread until the user clicks a button or |
||||
* closes the messagebox. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_ShowMessageBox(const SDL_MessageBoxData *messageboxdata, int *buttonid); |
||||
|
||||
/**
|
||||
* \brief Create a simple modal message box |
||||
* |
||||
* \param flags ::SDL_MessageBoxFlags |
||||
* \param title UTF-8 title text |
||||
* \param message UTF-8 message text |
||||
* \param window The parent window, or NULL for no parent |
||||
* |
||||
* \return 0 on success, -1 on error |
||||
* |
||||
* \sa SDL_ShowMessageBox |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_ShowSimpleMessageBox(Uint32 flags, const char *title, const char *message, SDL_Window *window); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_messagebox_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,302 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_mouse.h |
||||
* |
||||
* Include file for SDL mouse event handling. |
||||
*/ |
||||
|
||||
#ifndef SDL_mouse_h_ |
||||
#define SDL_mouse_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
#include "SDL_video.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
typedef struct SDL_Cursor SDL_Cursor; /**< Implementation dependent */ |
||||
|
||||
/**
|
||||
* \brief Cursor types for SDL_CreateSystemCursor(). |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_SYSTEM_CURSOR_ARROW, /**< Arrow */ |
||||
SDL_SYSTEM_CURSOR_IBEAM, /**< I-beam */ |
||||
SDL_SYSTEM_CURSOR_WAIT, /**< Wait */ |
||||
SDL_SYSTEM_CURSOR_CROSSHAIR, /**< Crosshair */ |
||||
SDL_SYSTEM_CURSOR_WAITARROW, /**< Small wait cursor (or Wait if not available) */ |
||||
SDL_SYSTEM_CURSOR_SIZENWSE, /**< Double arrow pointing northwest and southeast */ |
||||
SDL_SYSTEM_CURSOR_SIZENESW, /**< Double arrow pointing northeast and southwest */ |
||||
SDL_SYSTEM_CURSOR_SIZEWE, /**< Double arrow pointing west and east */ |
||||
SDL_SYSTEM_CURSOR_SIZENS, /**< Double arrow pointing north and south */ |
||||
SDL_SYSTEM_CURSOR_SIZEALL, /**< Four pointed arrow pointing north, south, east, and west */ |
||||
SDL_SYSTEM_CURSOR_NO, /**< Slashed circle or crossbones */ |
||||
SDL_SYSTEM_CURSOR_HAND, /**< Hand */ |
||||
SDL_NUM_SYSTEM_CURSORS |
||||
} SDL_SystemCursor; |
||||
|
||||
/**
|
||||
* \brief Scroll direction types for the Scroll event |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_MOUSEWHEEL_NORMAL, /**< The scroll direction is normal */ |
||||
SDL_MOUSEWHEEL_FLIPPED /**< The scroll direction is flipped / natural */ |
||||
} SDL_MouseWheelDirection; |
||||
|
||||
/* Function prototypes */ |
||||
|
||||
/**
|
||||
* \brief Get the window which currently has mouse focus. |
||||
*/ |
||||
extern DECLSPEC SDL_Window * SDLCALL SDL_GetMouseFocus(void); |
||||
|
||||
/**
|
||||
* \brief Retrieve the current state of the mouse. |
||||
* |
||||
* The current button state is returned as a button bitmask, which can |
||||
* be tested using the SDL_BUTTON(X) macros, and x and y are set to the |
||||
* mouse cursor position relative to the focus window for the currently |
||||
* selected mouse. You can pass NULL for either x or y. |
||||
*/ |
||||
extern DECLSPEC Uint32 SDLCALL SDL_GetMouseState(int *x, int *y); |
||||
|
||||
/**
|
||||
* \brief Get the current state of the mouse, in relation to the desktop |
||||
* |
||||
* This works just like SDL_GetMouseState(), but the coordinates will be |
||||
* reported relative to the top-left of the desktop. This can be useful if |
||||
* you need to track the mouse outside of a specific window and |
||||
* SDL_CaptureMouse() doesn't fit your needs. For example, it could be |
||||
* useful if you need to track the mouse while dragging a window, where |
||||
* coordinates relative to a window might not be in sync at all times. |
||||
* |
||||
* \note SDL_GetMouseState() returns the mouse position as SDL understands |
||||
* it from the last pump of the event queue. This function, however, |
||||
* queries the OS for the current mouse position, and as such, might |
||||
* be a slightly less efficient function. Unless you know what you're |
||||
* doing and have a good reason to use this function, you probably want |
||||
* SDL_GetMouseState() instead. |
||||
* |
||||
* \param x Returns the current X coord, relative to the desktop. Can be NULL. |
||||
* \param y Returns the current Y coord, relative to the desktop. Can be NULL. |
||||
* \return The current button state as a bitmask, which can be tested using the SDL_BUTTON(X) macros. |
||||
* |
||||
* \sa SDL_GetMouseState |
||||
*/ |
||||
extern DECLSPEC Uint32 SDLCALL SDL_GetGlobalMouseState(int *x, int *y); |
||||
|
||||
/**
|
||||
* \brief Retrieve the relative state of the mouse. |
||||
* |
||||
* The current button state is returned as a button bitmask, which can |
||||
* be tested using the SDL_BUTTON(X) macros, and x and y are set to the |
||||
* mouse deltas since the last call to SDL_GetRelativeMouseState(). |
||||
*/ |
||||
extern DECLSPEC Uint32 SDLCALL SDL_GetRelativeMouseState(int *x, int *y); |
||||
|
||||
/**
|
||||
* \brief Moves the mouse to the given position within the window. |
||||
* |
||||
* \param window The window to move the mouse into, or NULL for the current mouse focus |
||||
* \param x The x coordinate within the window |
||||
* \param y The y coordinate within the window |
||||
* |
||||
* \note This function generates a mouse motion event |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_WarpMouseInWindow(SDL_Window * window, |
||||
int x, int y); |
||||
|
||||
/**
|
||||
* \brief Moves the mouse to the given position in global screen space. |
||||
* |
||||
* \param x The x coordinate |
||||
* \param y The y coordinate |
||||
* \return 0 on success, -1 on error (usually: unsupported by a platform). |
||||
* |
||||
* \note This function generates a mouse motion event |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_WarpMouseGlobal(int x, int y); |
||||
|
||||
/**
|
||||
* \brief Set relative mouse mode. |
||||
* |
||||
* \param enabled Whether or not to enable relative mode |
||||
* |
||||
* \return 0 on success, or -1 if relative mode is not supported. |
||||
* |
||||
* While the mouse is in relative mode, the cursor is hidden, and the |
||||
* driver will try to report continuous motion in the current window. |
||||
* Only relative motion events will be delivered, the mouse position |
||||
* will not change. |
||||
* |
||||
* \note This function will flush any pending mouse motion. |
||||
* |
||||
* \sa SDL_GetRelativeMouseMode() |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SetRelativeMouseMode(SDL_bool enabled); |
||||
|
||||
/**
|
||||
* \brief Capture the mouse, to track input outside an SDL window. |
||||
* |
||||
* \param enabled Whether or not to enable capturing |
||||
* |
||||
* Capturing enables your app to obtain mouse events globally, instead of |
||||
* just within your window. Not all video targets support this function. |
||||
* When capturing is enabled, the current window will get all mouse events, |
||||
* but unlike relative mode, no change is made to the cursor and it is |
||||
* not restrained to your window. |
||||
* |
||||
* This function may also deny mouse input to other windows--both those in |
||||
* your application and others on the system--so you should use this |
||||
* function sparingly, and in small bursts. For example, you might want to |
||||
* track the mouse while the user is dragging something, until the user |
||||
* releases a mouse button. It is not recommended that you capture the mouse |
||||
* for long periods of time, such as the entire time your app is running. |
||||
* |
||||
* While captured, mouse events still report coordinates relative to the |
||||
* current (foreground) window, but those coordinates may be outside the |
||||
* bounds of the window (including negative values). Capturing is only |
||||
* allowed for the foreground window. If the window loses focus while |
||||
* capturing, the capture will be disabled automatically. |
||||
* |
||||
* While capturing is enabled, the current window will have the |
||||
* SDL_WINDOW_MOUSE_CAPTURE flag set. |
||||
* |
||||
* \return 0 on success, or -1 if not supported. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_CaptureMouse(SDL_bool enabled); |
||||
|
||||
/**
|
||||
* \brief Query whether relative mouse mode is enabled. |
||||
* |
||||
* \sa SDL_SetRelativeMouseMode() |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_GetRelativeMouseMode(void); |
||||
|
||||
/**
|
||||
* \brief Create a cursor, using the specified bitmap data and |
||||
* mask (in MSB format). |
||||
* |
||||
* The cursor width must be a multiple of 8 bits. |
||||
* |
||||
* The cursor is created in black and white according to the following: |
||||
* <table> |
||||
* <tr><td> data </td><td> mask </td><td> resulting pixel on screen </td></tr> |
||||
* <tr><td> 0 </td><td> 1 </td><td> White </td></tr> |
||||
* <tr><td> 1 </td><td> 1 </td><td> Black </td></tr> |
||||
* <tr><td> 0 </td><td> 0 </td><td> Transparent </td></tr> |
||||
* <tr><td> 1 </td><td> 0 </td><td> Inverted color if possible, black |
||||
* if not. </td></tr> |
||||
* </table> |
||||
* |
||||
* \sa SDL_FreeCursor() |
||||
*/ |
||||
extern DECLSPEC SDL_Cursor *SDLCALL SDL_CreateCursor(const Uint8 * data, |
||||
const Uint8 * mask, |
||||
int w, int h, int hot_x, |
||||
int hot_y); |
||||
|
||||
/**
|
||||
* \brief Create a color cursor. |
||||
* |
||||
* \sa SDL_FreeCursor() |
||||
*/ |
||||
extern DECLSPEC SDL_Cursor *SDLCALL SDL_CreateColorCursor(SDL_Surface *surface, |
||||
int hot_x, |
||||
int hot_y); |
||||
|
||||
/**
|
||||
* \brief Create a system cursor. |
||||
* |
||||
* \sa SDL_FreeCursor() |
||||
*/ |
||||
extern DECLSPEC SDL_Cursor *SDLCALL SDL_CreateSystemCursor(SDL_SystemCursor id); |
||||
|
||||
/**
|
||||
* \brief Set the active cursor. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_SetCursor(SDL_Cursor * cursor); |
||||
|
||||
/**
|
||||
* \brief Return the active cursor. |
||||
*/ |
||||
extern DECLSPEC SDL_Cursor *SDLCALL SDL_GetCursor(void); |
||||
|
||||
/**
|
||||
* \brief Return the default cursor. |
||||
*/ |
||||
extern DECLSPEC SDL_Cursor *SDLCALL SDL_GetDefaultCursor(void); |
||||
|
||||
/**
|
||||
* \brief Frees a cursor created with SDL_CreateCursor() or similar functions. |
||||
* |
||||
* \sa SDL_CreateCursor() |
||||
* \sa SDL_CreateColorCursor() |
||||
* \sa SDL_CreateSystemCursor() |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_FreeCursor(SDL_Cursor * cursor); |
||||
|
||||
/**
|
||||
* \brief Toggle whether or not the cursor is shown. |
||||
* |
||||
* \param toggle 1 to show the cursor, 0 to hide it, -1 to query the current |
||||
* state. |
||||
* |
||||
* \return 1 if the cursor is shown, or 0 if the cursor is hidden. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_ShowCursor(int toggle); |
||||
|
||||
/**
|
||||
* Used as a mask when testing buttons in buttonstate. |
||||
* - Button 1: Left mouse button |
||||
* - Button 2: Middle mouse button |
||||
* - Button 3: Right mouse button |
||||
*/ |
||||
#define SDL_BUTTON(X) (1 << ((X)-1)) |
||||
#define SDL_BUTTON_LEFT 1 |
||||
#define SDL_BUTTON_MIDDLE 2 |
||||
#define SDL_BUTTON_RIGHT 3 |
||||
#define SDL_BUTTON_X1 4 |
||||
#define SDL_BUTTON_X2 5 |
||||
#define SDL_BUTTON_LMASK SDL_BUTTON(SDL_BUTTON_LEFT) |
||||
#define SDL_BUTTON_MMASK SDL_BUTTON(SDL_BUTTON_MIDDLE) |
||||
#define SDL_BUTTON_RMASK SDL_BUTTON(SDL_BUTTON_RIGHT) |
||||
#define SDL_BUTTON_X1MASK SDL_BUTTON(SDL_BUTTON_X1) |
||||
#define SDL_BUTTON_X2MASK SDL_BUTTON(SDL_BUTTON_X2) |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_mouse_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,251 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
#ifndef SDL_mutex_h_ |
||||
#define SDL_mutex_h_ |
||||
|
||||
/**
|
||||
* \file SDL_mutex.h |
||||
* |
||||
* Functions to provide thread synchronization primitives. |
||||
*/ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* Synchronization functions which can time out return this value |
||||
* if they time out. |
||||
*/ |
||||
#define SDL_MUTEX_TIMEDOUT 1 |
||||
|
||||
/**
|
||||
* This is the timeout value which corresponds to never time out. |
||||
*/ |
||||
#define SDL_MUTEX_MAXWAIT (~(Uint32)0) |
||||
|
||||
|
||||
/**
|
||||
* \name Mutex functions |
||||
*/ |
||||
/* @{ */ |
||||
|
||||
/* The SDL mutex structure, defined in SDL_sysmutex.c */ |
||||
struct SDL_mutex; |
||||
typedef struct SDL_mutex SDL_mutex; |
||||
|
||||
/**
|
||||
* Create a mutex, initialized unlocked. |
||||
*/ |
||||
extern DECLSPEC SDL_mutex *SDLCALL SDL_CreateMutex(void); |
||||
|
||||
/**
|
||||
* Lock the mutex. |
||||
* |
||||
* \return 0, or -1 on error. |
||||
*/ |
||||
#define SDL_mutexP(m) SDL_LockMutex(m) |
||||
extern DECLSPEC int SDLCALL SDL_LockMutex(SDL_mutex * mutex); |
||||
|
||||
/**
|
||||
* Try to lock the mutex |
||||
* |
||||
* \return 0, SDL_MUTEX_TIMEDOUT, or -1 on error |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_TryLockMutex(SDL_mutex * mutex); |
||||
|
||||
/**
|
||||
* Unlock the mutex. |
||||
* |
||||
* \return 0, or -1 on error. |
||||
* |
||||
* \warning It is an error to unlock a mutex that has not been locked by |
||||
* the current thread, and doing so results in undefined behavior. |
||||
*/ |
||||
#define SDL_mutexV(m) SDL_UnlockMutex(m) |
||||
extern DECLSPEC int SDLCALL SDL_UnlockMutex(SDL_mutex * mutex); |
||||
|
||||
/**
|
||||
* Destroy a mutex. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_DestroyMutex(SDL_mutex * mutex); |
||||
|
||||
/* @} *//* Mutex functions */ |
||||
|
||||
|
||||
/**
|
||||
* \name Semaphore functions |
||||
*/ |
||||
/* @{ */ |
||||
|
||||
/* The SDL semaphore structure, defined in SDL_syssem.c */ |
||||
struct SDL_semaphore; |
||||
typedef struct SDL_semaphore SDL_sem; |
||||
|
||||
/**
|
||||
* Create a semaphore, initialized with value, returns NULL on failure. |
||||
*/ |
||||
extern DECLSPEC SDL_sem *SDLCALL SDL_CreateSemaphore(Uint32 initial_value); |
||||
|
||||
/**
|
||||
* Destroy a semaphore. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_DestroySemaphore(SDL_sem * sem); |
||||
|
||||
/**
|
||||
* This function suspends the calling thread until the semaphore pointed |
||||
* to by \c sem has a positive count. It then atomically decreases the |
||||
* semaphore count. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SemWait(SDL_sem * sem); |
||||
|
||||
/**
|
||||
* Non-blocking variant of SDL_SemWait(). |
||||
* |
||||
* \return 0 if the wait succeeds, ::SDL_MUTEX_TIMEDOUT if the wait would |
||||
* block, and -1 on error. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SemTryWait(SDL_sem * sem); |
||||
|
||||
/**
|
||||
* Variant of SDL_SemWait() with a timeout in milliseconds. |
||||
* |
||||
* \return 0 if the wait succeeds, ::SDL_MUTEX_TIMEDOUT if the wait does not |
||||
* succeed in the allotted time, and -1 on error. |
||||
* |
||||
* \warning On some platforms this function is implemented by looping with a |
||||
* delay of 1 ms, and so should be avoided if possible. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SemWaitTimeout(SDL_sem * sem, Uint32 ms); |
||||
|
||||
/**
|
||||
* Atomically increases the semaphore's count (not blocking). |
||||
* |
||||
* \return 0, or -1 on error. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SemPost(SDL_sem * sem); |
||||
|
||||
/**
|
||||
* Returns the current count of the semaphore. |
||||
*/ |
||||
extern DECLSPEC Uint32 SDLCALL SDL_SemValue(SDL_sem * sem); |
||||
|
||||
/* @} *//* Semaphore functions */ |
||||
|
||||
|
||||
/**
|
||||
* \name Condition variable functions |
||||
*/ |
||||
/* @{ */ |
||||
|
||||
/* The SDL condition variable structure, defined in SDL_syscond.c */ |
||||
struct SDL_cond; |
||||
typedef struct SDL_cond SDL_cond; |
||||
|
||||
/**
|
||||
* Create a condition variable. |
||||
* |
||||
* Typical use of condition variables: |
||||
* |
||||
* Thread A: |
||||
* SDL_LockMutex(lock); |
||||
* while ( ! condition ) { |
||||
* SDL_CondWait(cond, lock); |
||||
* } |
||||
* SDL_UnlockMutex(lock); |
||||
* |
||||
* Thread B: |
||||
* SDL_LockMutex(lock); |
||||
* ... |
||||
* condition = true; |
||||
* ... |
||||
* SDL_CondSignal(cond); |
||||
* SDL_UnlockMutex(lock); |
||||
* |
||||
* There is some discussion whether to signal the condition variable |
||||
* with the mutex locked or not. There is some potential performance |
||||
* benefit to unlocking first on some platforms, but there are some |
||||
* potential race conditions depending on how your code is structured. |
||||
* |
||||
* In general it's safer to signal the condition variable while the |
||||
* mutex is locked. |
||||
*/ |
||||
extern DECLSPEC SDL_cond *SDLCALL SDL_CreateCond(void); |
||||
|
||||
/**
|
||||
* Destroy a condition variable. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_DestroyCond(SDL_cond * cond); |
||||
|
||||
/**
|
||||
* Restart one of the threads that are waiting on the condition variable. |
||||
* |
||||
* \return 0 or -1 on error. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_CondSignal(SDL_cond * cond); |
||||
|
||||
/**
|
||||
* Restart all threads that are waiting on the condition variable. |
||||
* |
||||
* \return 0 or -1 on error. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_CondBroadcast(SDL_cond * cond); |
||||
|
||||
/**
|
||||
* Wait on the condition variable, unlocking the provided mutex. |
||||
* |
||||
* \warning The mutex must be locked before entering this function! |
||||
* |
||||
* The mutex is re-locked once the condition variable is signaled. |
||||
* |
||||
* \return 0 when it is signaled, or -1 on error. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_CondWait(SDL_cond * cond, SDL_mutex * mutex); |
||||
|
||||
/**
|
||||
* Waits for at most \c ms milliseconds, and returns 0 if the condition |
||||
* variable is signaled, ::SDL_MUTEX_TIMEDOUT if the condition is not |
||||
* signaled in the allotted time, and -1 on error. |
||||
* |
||||
* \warning On some platforms this function is implemented by looping with a |
||||
* delay of 1 ms, and so should be avoided if possible. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_CondWaitTimeout(SDL_cond * cond, |
||||
SDL_mutex * mutex, Uint32 ms); |
||||
|
||||
/* @} *//* Condition variable functions */ |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_mutex_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,33 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
#ifndef SDLname_h_ |
||||
#define SDLname_h_ |
||||
|
||||
#if defined(__STDC__) || defined(__cplusplus) |
||||
#define NeedFunctionPrototypes 1 |
||||
#endif |
||||
|
||||
#define SDL_NAME(X) SDL_##X |
||||
|
||||
#endif /* SDLname_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,39 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_opengles.h |
||||
* |
||||
* This is a simple file to encapsulate the OpenGL ES 1.X API headers. |
||||
*/ |
||||
#include "SDL_config.h" |
||||
|
||||
#ifdef __IPHONEOS__ |
||||
#include <OpenGLES/ES1/gl.h> |
||||
#include <OpenGLES/ES1/glext.h> |
||||
#else |
||||
#include <GLES/gl.h> |
||||
#include <GLES/glext.h> |
||||
#endif |
||||
|
||||
#ifndef APIENTRY |
||||
#define APIENTRY |
||||
#endif |
||||
@ -0,0 +1,52 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_opengles2.h |
||||
* |
||||
* This is a simple file to encapsulate the OpenGL ES 2.0 API headers. |
||||
*/ |
||||
#include "SDL_config.h" |
||||
|
||||
#ifndef _MSC_VER |
||||
|
||||
#ifdef __IPHONEOS__ |
||||
#include <OpenGLES/ES2/gl.h> |
||||
#include <OpenGLES/ES2/glext.h> |
||||
#else |
||||
#include <GLES2/gl2platform.h> |
||||
#include <GLES2/gl2.h> |
||||
#include <GLES2/gl2ext.h> |
||||
#endif |
||||
|
||||
#else /* _MSC_VER */ |
||||
|
||||
/* OpenGL ES2 headers for Visual Studio */ |
||||
#include "SDL_opengles2_khrplatform.h" |
||||
#include "SDL_opengles2_gl2platform.h" |
||||
#include "SDL_opengles2_gl2.h" |
||||
#include "SDL_opengles2_gl2ext.h" |
||||
|
||||
#endif /* _MSC_VER */ |
||||
|
||||
#ifndef APIENTRY |
||||
#define APIENTRY GL_APIENTRY |
||||
#endif |
||||
@ -0,0 +1,621 @@ |
||||
#ifndef __gl2_h_ |
||||
#define __gl2_h_ |
||||
|
||||
/* $Revision: 20555 $ on $Date:: 2013-02-12 14:32:47 -0800 #$ */ |
||||
|
||||
/*#include <GLES2/gl2platform.h>*/ |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/*
|
||||
* This document is licensed under the SGI Free Software B License Version |
||||
* 2.0. For details, see http://oss.sgi.com/projects/FreeB/ .
|
||||
*/ |
||||
|
||||
/*-------------------------------------------------------------------------
|
||||
* Data type definitions |
||||
*-----------------------------------------------------------------------*/ |
||||
|
||||
typedef void GLvoid; |
||||
typedef char GLchar; |
||||
typedef unsigned int GLenum; |
||||
typedef unsigned char GLboolean; |
||||
typedef unsigned int GLbitfield; |
||||
typedef khronos_int8_t GLbyte; |
||||
typedef short GLshort; |
||||
typedef int GLint; |
||||
typedef int GLsizei; |
||||
typedef khronos_uint8_t GLubyte; |
||||
typedef unsigned short GLushort; |
||||
typedef unsigned int GLuint; |
||||
typedef khronos_float_t GLfloat; |
||||
typedef khronos_float_t GLclampf; |
||||
typedef khronos_int32_t GLfixed; |
||||
|
||||
/* GL types for handling large vertex buffer objects */ |
||||
typedef khronos_intptr_t GLintptr; |
||||
typedef khronos_ssize_t GLsizeiptr; |
||||
|
||||
/* OpenGL ES core versions */ |
||||
#define GL_ES_VERSION_2_0 1 |
||||
|
||||
/* ClearBufferMask */ |
||||
#define GL_DEPTH_BUFFER_BIT 0x00000100 |
||||
#define GL_STENCIL_BUFFER_BIT 0x00000400 |
||||
#define GL_COLOR_BUFFER_BIT 0x00004000 |
||||
|
||||
/* Boolean */ |
||||
#define GL_FALSE 0 |
||||
#define GL_TRUE 1 |
||||
|
||||
/* BeginMode */ |
||||
#define GL_POINTS 0x0000 |
||||
#define GL_LINES 0x0001 |
||||
#define GL_LINE_LOOP 0x0002 |
||||
#define GL_LINE_STRIP 0x0003 |
||||
#define GL_TRIANGLES 0x0004 |
||||
#define GL_TRIANGLE_STRIP 0x0005 |
||||
#define GL_TRIANGLE_FAN 0x0006 |
||||
|
||||
/* AlphaFunction (not supported in ES20) */ |
||||
/* GL_NEVER */ |
||||
/* GL_LESS */ |
||||
/* GL_EQUAL */ |
||||
/* GL_LEQUAL */ |
||||
/* GL_GREATER */ |
||||
/* GL_NOTEQUAL */ |
||||
/* GL_GEQUAL */ |
||||
/* GL_ALWAYS */ |
||||
|
||||
/* BlendingFactorDest */ |
||||
#define GL_ZERO 0 |
||||
#define GL_ONE 1 |
||||
#define GL_SRC_COLOR 0x0300 |
||||
#define GL_ONE_MINUS_SRC_COLOR 0x0301 |
||||
#define GL_SRC_ALPHA 0x0302 |
||||
#define GL_ONE_MINUS_SRC_ALPHA 0x0303 |
||||
#define GL_DST_ALPHA 0x0304 |
||||
#define GL_ONE_MINUS_DST_ALPHA 0x0305 |
||||
|
||||
/* BlendingFactorSrc */ |
||||
/* GL_ZERO */ |
||||
/* GL_ONE */ |
||||
#define GL_DST_COLOR 0x0306 |
||||
#define GL_ONE_MINUS_DST_COLOR 0x0307 |
||||
#define GL_SRC_ALPHA_SATURATE 0x0308 |
||||
/* GL_SRC_ALPHA */ |
||||
/* GL_ONE_MINUS_SRC_ALPHA */ |
||||
/* GL_DST_ALPHA */ |
||||
/* GL_ONE_MINUS_DST_ALPHA */ |
||||
|
||||
/* BlendEquationSeparate */ |
||||
#define GL_FUNC_ADD 0x8006 |
||||
#define GL_BLEND_EQUATION 0x8009 |
||||
#define GL_BLEND_EQUATION_RGB 0x8009 /* same as BLEND_EQUATION */ |
||||
#define GL_BLEND_EQUATION_ALPHA 0x883D |
||||
|
||||
/* BlendSubtract */ |
||||
#define GL_FUNC_SUBTRACT 0x800A |
||||
#define GL_FUNC_REVERSE_SUBTRACT 0x800B |
||||
|
||||
/* Separate Blend Functions */ |
||||
#define GL_BLEND_DST_RGB 0x80C8 |
||||
#define GL_BLEND_SRC_RGB 0x80C9 |
||||
#define GL_BLEND_DST_ALPHA 0x80CA |
||||
#define GL_BLEND_SRC_ALPHA 0x80CB |
||||
#define GL_CONSTANT_COLOR 0x8001 |
||||
#define GL_ONE_MINUS_CONSTANT_COLOR 0x8002 |
||||
#define GL_CONSTANT_ALPHA 0x8003 |
||||
#define GL_ONE_MINUS_CONSTANT_ALPHA 0x8004 |
||||
#define GL_BLEND_COLOR 0x8005 |
||||
|
||||
/* Buffer Objects */ |
||||
#define GL_ARRAY_BUFFER 0x8892 |
||||
#define GL_ELEMENT_ARRAY_BUFFER 0x8893 |
||||
#define GL_ARRAY_BUFFER_BINDING 0x8894 |
||||
#define GL_ELEMENT_ARRAY_BUFFER_BINDING 0x8895 |
||||
|
||||
#define GL_STREAM_DRAW 0x88E0 |
||||
#define GL_STATIC_DRAW 0x88E4 |
||||
#define GL_DYNAMIC_DRAW 0x88E8 |
||||
|
||||
#define GL_BUFFER_SIZE 0x8764 |
||||
#define GL_BUFFER_USAGE 0x8765 |
||||
|
||||
#define GL_CURRENT_VERTEX_ATTRIB 0x8626 |
||||
|
||||
/* CullFaceMode */ |
||||
#define GL_FRONT 0x0404 |
||||
#define GL_BACK 0x0405 |
||||
#define GL_FRONT_AND_BACK 0x0408 |
||||
|
||||
/* DepthFunction */ |
||||
/* GL_NEVER */ |
||||
/* GL_LESS */ |
||||
/* GL_EQUAL */ |
||||
/* GL_LEQUAL */ |
||||
/* GL_GREATER */ |
||||
/* GL_NOTEQUAL */ |
||||
/* GL_GEQUAL */ |
||||
/* GL_ALWAYS */ |
||||
|
||||
/* EnableCap */ |
||||
#define GL_TEXTURE_2D 0x0DE1 |
||||
#define GL_CULL_FACE 0x0B44 |
||||
#define GL_BLEND 0x0BE2 |
||||
#define GL_DITHER 0x0BD0 |
||||
#define GL_STENCIL_TEST 0x0B90 |
||||
#define GL_DEPTH_TEST 0x0B71 |
||||
#define GL_SCISSOR_TEST 0x0C11 |
||||
#define GL_POLYGON_OFFSET_FILL 0x8037 |
||||
#define GL_SAMPLE_ALPHA_TO_COVERAGE 0x809E |
||||
#define GL_SAMPLE_COVERAGE 0x80A0 |
||||
|
||||
/* ErrorCode */ |
||||
#define GL_NO_ERROR 0 |
||||
#define GL_INVALID_ENUM 0x0500 |
||||
#define GL_INVALID_VALUE 0x0501 |
||||
#define GL_INVALID_OPERATION 0x0502 |
||||
#define GL_OUT_OF_MEMORY 0x0505 |
||||
|
||||
/* FrontFaceDirection */ |
||||
#define GL_CW 0x0900 |
||||
#define GL_CCW 0x0901 |
||||
|
||||
/* GetPName */ |
||||
#define GL_LINE_WIDTH 0x0B21 |
||||
#define GL_ALIASED_POINT_SIZE_RANGE 0x846D |
||||
#define GL_ALIASED_LINE_WIDTH_RANGE 0x846E |
||||
#define GL_CULL_FACE_MODE 0x0B45 |
||||
#define GL_FRONT_FACE 0x0B46 |
||||
#define GL_DEPTH_RANGE 0x0B70 |
||||
#define GL_DEPTH_WRITEMASK 0x0B72 |
||||
#define GL_DEPTH_CLEAR_VALUE 0x0B73 |
||||
#define GL_DEPTH_FUNC 0x0B74 |
||||
#define GL_STENCIL_CLEAR_VALUE 0x0B91 |
||||
#define GL_STENCIL_FUNC 0x0B92 |
||||
#define GL_STENCIL_FAIL 0x0B94 |
||||
#define GL_STENCIL_PASS_DEPTH_FAIL 0x0B95 |
||||
#define GL_STENCIL_PASS_DEPTH_PASS 0x0B96 |
||||
#define GL_STENCIL_REF 0x0B97 |
||||
#define GL_STENCIL_VALUE_MASK 0x0B93 |
||||
#define GL_STENCIL_WRITEMASK 0x0B98 |
||||
#define GL_STENCIL_BACK_FUNC 0x8800 |
||||
#define GL_STENCIL_BACK_FAIL 0x8801 |
||||
#define GL_STENCIL_BACK_PASS_DEPTH_FAIL 0x8802 |
||||
#define GL_STENCIL_BACK_PASS_DEPTH_PASS 0x8803 |
||||
#define GL_STENCIL_BACK_REF 0x8CA3 |
||||
#define GL_STENCIL_BACK_VALUE_MASK 0x8CA4 |
||||
#define GL_STENCIL_BACK_WRITEMASK 0x8CA5 |
||||
#define GL_VIEWPORT 0x0BA2 |
||||
#define GL_SCISSOR_BOX 0x0C10 |
||||
/* GL_SCISSOR_TEST */ |
||||
#define GL_COLOR_CLEAR_VALUE 0x0C22 |
||||
#define GL_COLOR_WRITEMASK 0x0C23 |
||||
#define GL_UNPACK_ALIGNMENT 0x0CF5 |
||||
#define GL_PACK_ALIGNMENT 0x0D05 |
||||
#define GL_MAX_TEXTURE_SIZE 0x0D33 |
||||
#define GL_MAX_VIEWPORT_DIMS 0x0D3A |
||||
#define GL_SUBPIXEL_BITS 0x0D50 |
||||
#define GL_RED_BITS 0x0D52 |
||||
#define GL_GREEN_BITS 0x0D53 |
||||
#define GL_BLUE_BITS 0x0D54 |
||||
#define GL_ALPHA_BITS 0x0D55 |
||||
#define GL_DEPTH_BITS 0x0D56 |
||||
#define GL_STENCIL_BITS 0x0D57 |
||||
#define GL_POLYGON_OFFSET_UNITS 0x2A00 |
||||
/* GL_POLYGON_OFFSET_FILL */ |
||||
#define GL_POLYGON_OFFSET_FACTOR 0x8038 |
||||
#define GL_TEXTURE_BINDING_2D 0x8069 |
||||
#define GL_SAMPLE_BUFFERS 0x80A8 |
||||
#define GL_SAMPLES 0x80A9 |
||||
#define GL_SAMPLE_COVERAGE_VALUE 0x80AA |
||||
#define GL_SAMPLE_COVERAGE_INVERT 0x80AB |
||||
|
||||
/* GetTextureParameter */ |
||||
/* GL_TEXTURE_MAG_FILTER */ |
||||
/* GL_TEXTURE_MIN_FILTER */ |
||||
/* GL_TEXTURE_WRAP_S */ |
||||
/* GL_TEXTURE_WRAP_T */ |
||||
|
||||
#define GL_NUM_COMPRESSED_TEXTURE_FORMATS 0x86A2 |
||||
#define GL_COMPRESSED_TEXTURE_FORMATS 0x86A3 |
||||
|
||||
/* HintMode */ |
||||
#define GL_DONT_CARE 0x1100 |
||||
#define GL_FASTEST 0x1101 |
||||
#define GL_NICEST 0x1102 |
||||
|
||||
/* HintTarget */ |
||||
#define GL_GENERATE_MIPMAP_HINT 0x8192 |
||||
|
||||
/* DataType */ |
||||
#define GL_BYTE 0x1400 |
||||
#define GL_UNSIGNED_BYTE 0x1401 |
||||
#define GL_SHORT 0x1402 |
||||
#define GL_UNSIGNED_SHORT 0x1403 |
||||
#define GL_INT 0x1404 |
||||
#define GL_UNSIGNED_INT 0x1405 |
||||
#define GL_FLOAT 0x1406 |
||||
#define GL_FIXED 0x140C |
||||
|
||||
/* PixelFormat */ |
||||
#define GL_DEPTH_COMPONENT 0x1902 |
||||
#define GL_ALPHA 0x1906 |
||||
#define GL_RGB 0x1907 |
||||
#define GL_RGBA 0x1908 |
||||
#define GL_LUMINANCE 0x1909 |
||||
#define GL_LUMINANCE_ALPHA 0x190A |
||||
|
||||
/* PixelType */ |
||||
/* GL_UNSIGNED_BYTE */ |
||||
#define GL_UNSIGNED_SHORT_4_4_4_4 0x8033 |
||||
#define GL_UNSIGNED_SHORT_5_5_5_1 0x8034 |
||||
#define GL_UNSIGNED_SHORT_5_6_5 0x8363 |
||||
|
||||
/* Shaders */ |
||||
#define GL_FRAGMENT_SHADER 0x8B30 |
||||
#define GL_VERTEX_SHADER 0x8B31 |
||||
#define GL_MAX_VERTEX_ATTRIBS 0x8869 |
||||
#define GL_MAX_VERTEX_UNIFORM_VECTORS 0x8DFB |
||||
#define GL_MAX_VARYING_VECTORS 0x8DFC |
||||
#define GL_MAX_COMBINED_TEXTURE_IMAGE_UNITS 0x8B4D |
||||
#define GL_MAX_VERTEX_TEXTURE_IMAGE_UNITS 0x8B4C |
||||
#define GL_MAX_TEXTURE_IMAGE_UNITS 0x8872 |
||||
#define GL_MAX_FRAGMENT_UNIFORM_VECTORS 0x8DFD |
||||
#define GL_SHADER_TYPE 0x8B4F |
||||
#define GL_DELETE_STATUS 0x8B80 |
||||
#define GL_LINK_STATUS 0x8B82 |
||||
#define GL_VALIDATE_STATUS 0x8B83 |
||||
#define GL_ATTACHED_SHADERS 0x8B85 |
||||
#define GL_ACTIVE_UNIFORMS 0x8B86 |
||||
#define GL_ACTIVE_UNIFORM_MAX_LENGTH 0x8B87 |
||||
#define GL_ACTIVE_ATTRIBUTES 0x8B89 |
||||
#define GL_ACTIVE_ATTRIBUTE_MAX_LENGTH 0x8B8A |
||||
#define GL_SHADING_LANGUAGE_VERSION 0x8B8C |
||||
#define GL_CURRENT_PROGRAM 0x8B8D |
||||
|
||||
/* StencilFunction */ |
||||
#define GL_NEVER 0x0200 |
||||
#define GL_LESS 0x0201 |
||||
#define GL_EQUAL 0x0202 |
||||
#define GL_LEQUAL 0x0203 |
||||
#define GL_GREATER 0x0204 |
||||
#define GL_NOTEQUAL 0x0205 |
||||
#define GL_GEQUAL 0x0206 |
||||
#define GL_ALWAYS 0x0207 |
||||
|
||||
/* StencilOp */ |
||||
/* GL_ZERO */ |
||||
#define GL_KEEP 0x1E00 |
||||
#define GL_REPLACE 0x1E01 |
||||
#define GL_INCR 0x1E02 |
||||
#define GL_DECR 0x1E03 |
||||
#define GL_INVERT 0x150A |
||||
#define GL_INCR_WRAP 0x8507 |
||||
#define GL_DECR_WRAP 0x8508 |
||||
|
||||
/* StringName */ |
||||
#define GL_VENDOR 0x1F00 |
||||
#define GL_RENDERER 0x1F01 |
||||
#define GL_VERSION 0x1F02 |
||||
#define GL_EXTENSIONS 0x1F03 |
||||
|
||||
/* TextureMagFilter */ |
||||
#define GL_NEAREST 0x2600 |
||||
#define GL_LINEAR 0x2601 |
||||
|
||||
/* TextureMinFilter */ |
||||
/* GL_NEAREST */ |
||||
/* GL_LINEAR */ |
||||
#define GL_NEAREST_MIPMAP_NEAREST 0x2700 |
||||
#define GL_LINEAR_MIPMAP_NEAREST 0x2701 |
||||
#define GL_NEAREST_MIPMAP_LINEAR 0x2702 |
||||
#define GL_LINEAR_MIPMAP_LINEAR 0x2703 |
||||
|
||||
/* TextureParameterName */ |
||||
#define GL_TEXTURE_MAG_FILTER 0x2800 |
||||
#define GL_TEXTURE_MIN_FILTER 0x2801 |
||||
#define GL_TEXTURE_WRAP_S 0x2802 |
||||
#define GL_TEXTURE_WRAP_T 0x2803 |
||||
|
||||
/* TextureTarget */ |
||||
/* GL_TEXTURE_2D */ |
||||
#define GL_TEXTURE 0x1702 |
||||
|
||||
#define GL_TEXTURE_CUBE_MAP 0x8513 |
||||
#define GL_TEXTURE_BINDING_CUBE_MAP 0x8514 |
||||
#define GL_TEXTURE_CUBE_MAP_POSITIVE_X 0x8515 |
||||
#define GL_TEXTURE_CUBE_MAP_NEGATIVE_X 0x8516 |
||||
#define GL_TEXTURE_CUBE_MAP_POSITIVE_Y 0x8517 |
||||
#define GL_TEXTURE_CUBE_MAP_NEGATIVE_Y 0x8518 |
||||
#define GL_TEXTURE_CUBE_MAP_POSITIVE_Z 0x8519 |
||||
#define GL_TEXTURE_CUBE_MAP_NEGATIVE_Z 0x851A |
||||
#define GL_MAX_CUBE_MAP_TEXTURE_SIZE 0x851C |
||||
|
||||
/* TextureUnit */ |
||||
#define GL_TEXTURE0 0x84C0 |
||||
#define GL_TEXTURE1 0x84C1 |
||||
#define GL_TEXTURE2 0x84C2 |
||||
#define GL_TEXTURE3 0x84C3 |
||||
#define GL_TEXTURE4 0x84C4 |
||||
#define GL_TEXTURE5 0x84C5 |
||||
#define GL_TEXTURE6 0x84C6 |
||||
#define GL_TEXTURE7 0x84C7 |
||||
#define GL_TEXTURE8 0x84C8 |
||||
#define GL_TEXTURE9 0x84C9 |
||||
#define GL_TEXTURE10 0x84CA |
||||
#define GL_TEXTURE11 0x84CB |
||||
#define GL_TEXTURE12 0x84CC |
||||
#define GL_TEXTURE13 0x84CD |
||||
#define GL_TEXTURE14 0x84CE |
||||
#define GL_TEXTURE15 0x84CF |
||||
#define GL_TEXTURE16 0x84D0 |
||||
#define GL_TEXTURE17 0x84D1 |
||||
#define GL_TEXTURE18 0x84D2 |
||||
#define GL_TEXTURE19 0x84D3 |
||||
#define GL_TEXTURE20 0x84D4 |
||||
#define GL_TEXTURE21 0x84D5 |
||||
#define GL_TEXTURE22 0x84D6 |
||||
#define GL_TEXTURE23 0x84D7 |
||||
#define GL_TEXTURE24 0x84D8 |
||||
#define GL_TEXTURE25 0x84D9 |
||||
#define GL_TEXTURE26 0x84DA |
||||
#define GL_TEXTURE27 0x84DB |
||||
#define GL_TEXTURE28 0x84DC |
||||
#define GL_TEXTURE29 0x84DD |
||||
#define GL_TEXTURE30 0x84DE |
||||
#define GL_TEXTURE31 0x84DF |
||||
#define GL_ACTIVE_TEXTURE 0x84E0 |
||||
|
||||
/* TextureWrapMode */ |
||||
#define GL_REPEAT 0x2901 |
||||
#define GL_CLAMP_TO_EDGE 0x812F |
||||
#define GL_MIRRORED_REPEAT 0x8370 |
||||
|
||||
/* Uniform Types */ |
||||
#define GL_FLOAT_VEC2 0x8B50 |
||||
#define GL_FLOAT_VEC3 0x8B51 |
||||
#define GL_FLOAT_VEC4 0x8B52 |
||||
#define GL_INT_VEC2 0x8B53 |
||||
#define GL_INT_VEC3 0x8B54 |
||||
#define GL_INT_VEC4 0x8B55 |
||||
#define GL_BOOL 0x8B56 |
||||
#define GL_BOOL_VEC2 0x8B57 |
||||
#define GL_BOOL_VEC3 0x8B58 |
||||
#define GL_BOOL_VEC4 0x8B59 |
||||
#define GL_FLOAT_MAT2 0x8B5A |
||||
#define GL_FLOAT_MAT3 0x8B5B |
||||
#define GL_FLOAT_MAT4 0x8B5C |
||||
#define GL_SAMPLER_2D 0x8B5E |
||||
#define GL_SAMPLER_CUBE 0x8B60 |
||||
|
||||
/* Vertex Arrays */ |
||||
#define GL_VERTEX_ATTRIB_ARRAY_ENABLED 0x8622 |
||||
#define GL_VERTEX_ATTRIB_ARRAY_SIZE 0x8623 |
||||
#define GL_VERTEX_ATTRIB_ARRAY_STRIDE 0x8624 |
||||
#define GL_VERTEX_ATTRIB_ARRAY_TYPE 0x8625 |
||||
#define GL_VERTEX_ATTRIB_ARRAY_NORMALIZED 0x886A |
||||
#define GL_VERTEX_ATTRIB_ARRAY_POINTER 0x8645 |
||||
#define GL_VERTEX_ATTRIB_ARRAY_BUFFER_BINDING 0x889F |
||||
|
||||
/* Read Format */ |
||||
#define GL_IMPLEMENTATION_COLOR_READ_TYPE 0x8B9A |
||||
#define GL_IMPLEMENTATION_COLOR_READ_FORMAT 0x8B9B |
||||
|
||||
/* Shader Source */ |
||||
#define GL_COMPILE_STATUS 0x8B81 |
||||
#define GL_INFO_LOG_LENGTH 0x8B84 |
||||
#define GL_SHADER_SOURCE_LENGTH 0x8B88 |
||||
#define GL_SHADER_COMPILER 0x8DFA |
||||
|
||||
/* Shader Binary */ |
||||
#define GL_SHADER_BINARY_FORMATS 0x8DF8 |
||||
#define GL_NUM_SHADER_BINARY_FORMATS 0x8DF9 |
||||
|
||||
/* Shader Precision-Specified Types */ |
||||
#define GL_LOW_FLOAT 0x8DF0 |
||||
#define GL_MEDIUM_FLOAT 0x8DF1 |
||||
#define GL_HIGH_FLOAT 0x8DF2 |
||||
#define GL_LOW_INT 0x8DF3 |
||||
#define GL_MEDIUM_INT 0x8DF4 |
||||
#define GL_HIGH_INT 0x8DF5 |
||||
|
||||
/* Framebuffer Object. */ |
||||
#define GL_FRAMEBUFFER 0x8D40 |
||||
#define GL_RENDERBUFFER 0x8D41 |
||||
|
||||
#define GL_RGBA4 0x8056 |
||||
#define GL_RGB5_A1 0x8057 |
||||
#define GL_RGB565 0x8D62 |
||||
#define GL_DEPTH_COMPONENT16 0x81A5 |
||||
#define GL_STENCIL_INDEX8 0x8D48 |
||||
|
||||
#define GL_RENDERBUFFER_WIDTH 0x8D42 |
||||
#define GL_RENDERBUFFER_HEIGHT 0x8D43 |
||||
#define GL_RENDERBUFFER_INTERNAL_FORMAT 0x8D44 |
||||
#define GL_RENDERBUFFER_RED_SIZE 0x8D50 |
||||
#define GL_RENDERBUFFER_GREEN_SIZE 0x8D51 |
||||
#define GL_RENDERBUFFER_BLUE_SIZE 0x8D52 |
||||
#define GL_RENDERBUFFER_ALPHA_SIZE 0x8D53 |
||||
#define GL_RENDERBUFFER_DEPTH_SIZE 0x8D54 |
||||
#define GL_RENDERBUFFER_STENCIL_SIZE 0x8D55 |
||||
|
||||
#define GL_FRAMEBUFFER_ATTACHMENT_OBJECT_TYPE 0x8CD0 |
||||
#define GL_FRAMEBUFFER_ATTACHMENT_OBJECT_NAME 0x8CD1 |
||||
#define GL_FRAMEBUFFER_ATTACHMENT_TEXTURE_LEVEL 0x8CD2 |
||||
#define GL_FRAMEBUFFER_ATTACHMENT_TEXTURE_CUBE_MAP_FACE 0x8CD3 |
||||
|
||||
#define GL_COLOR_ATTACHMENT0 0x8CE0 |
||||
#define GL_DEPTH_ATTACHMENT 0x8D00 |
||||
#define GL_STENCIL_ATTACHMENT 0x8D20 |
||||
|
||||
#define GL_NONE 0 |
||||
|
||||
#define GL_FRAMEBUFFER_COMPLETE 0x8CD5 |
||||
#define GL_FRAMEBUFFER_INCOMPLETE_ATTACHMENT 0x8CD6 |
||||
#define GL_FRAMEBUFFER_INCOMPLETE_MISSING_ATTACHMENT 0x8CD7 |
||||
#define GL_FRAMEBUFFER_INCOMPLETE_DIMENSIONS 0x8CD9 |
||||
#define GL_FRAMEBUFFER_UNSUPPORTED 0x8CDD |
||||
|
||||
#define GL_FRAMEBUFFER_BINDING 0x8CA6 |
||||
#define GL_RENDERBUFFER_BINDING 0x8CA7 |
||||
#define GL_MAX_RENDERBUFFER_SIZE 0x84E8 |
||||
|
||||
#define GL_INVALID_FRAMEBUFFER_OPERATION 0x0506 |
||||
|
||||
/*-------------------------------------------------------------------------
|
||||
* GL core functions. |
||||
*-----------------------------------------------------------------------*/ |
||||
|
||||
GL_APICALL void GL_APIENTRY glActiveTexture (GLenum texture); |
||||
GL_APICALL void GL_APIENTRY glAttachShader (GLuint program, GLuint shader); |
||||
GL_APICALL void GL_APIENTRY glBindAttribLocation (GLuint program, GLuint index, const GLchar* name); |
||||
GL_APICALL void GL_APIENTRY glBindBuffer (GLenum target, GLuint buffer); |
||||
GL_APICALL void GL_APIENTRY glBindFramebuffer (GLenum target, GLuint framebuffer); |
||||
GL_APICALL void GL_APIENTRY glBindRenderbuffer (GLenum target, GLuint renderbuffer); |
||||
GL_APICALL void GL_APIENTRY glBindTexture (GLenum target, GLuint texture); |
||||
GL_APICALL void GL_APIENTRY glBlendColor (GLclampf red, GLclampf green, GLclampf blue, GLclampf alpha); |
||||
GL_APICALL void GL_APIENTRY glBlendEquation ( GLenum mode ); |
||||
GL_APICALL void GL_APIENTRY glBlendEquationSeparate (GLenum modeRGB, GLenum modeAlpha); |
||||
GL_APICALL void GL_APIENTRY glBlendFunc (GLenum sfactor, GLenum dfactor); |
||||
GL_APICALL void GL_APIENTRY glBlendFuncSeparate (GLenum srcRGB, GLenum dstRGB, GLenum srcAlpha, GLenum dstAlpha); |
||||
GL_APICALL void GL_APIENTRY glBufferData (GLenum target, GLsizeiptr size, const GLvoid* data, GLenum usage); |
||||
GL_APICALL void GL_APIENTRY glBufferSubData (GLenum target, GLintptr offset, GLsizeiptr size, const GLvoid* data); |
||||
GL_APICALL GLenum GL_APIENTRY glCheckFramebufferStatus (GLenum target); |
||||
GL_APICALL void GL_APIENTRY glClear (GLbitfield mask); |
||||
GL_APICALL void GL_APIENTRY glClearColor (GLclampf red, GLclampf green, GLclampf blue, GLclampf alpha); |
||||
GL_APICALL void GL_APIENTRY glClearDepthf (GLclampf depth); |
||||
GL_APICALL void GL_APIENTRY glClearStencil (GLint s); |
||||
GL_APICALL void GL_APIENTRY glColorMask (GLboolean red, GLboolean green, GLboolean blue, GLboolean alpha); |
||||
GL_APICALL void GL_APIENTRY glCompileShader (GLuint shader); |
||||
GL_APICALL void GL_APIENTRY glCompressedTexImage2D (GLenum target, GLint level, GLenum internalformat, GLsizei width, GLsizei height, GLint border, GLsizei imageSize, const GLvoid* data); |
||||
GL_APICALL void GL_APIENTRY glCompressedTexSubImage2D (GLenum target, GLint level, GLint xoffset, GLint yoffset, GLsizei width, GLsizei height, GLenum format, GLsizei imageSize, const GLvoid* data); |
||||
GL_APICALL void GL_APIENTRY glCopyTexImage2D (GLenum target, GLint level, GLenum internalformat, GLint x, GLint y, GLsizei width, GLsizei height, GLint border); |
||||
GL_APICALL void GL_APIENTRY glCopyTexSubImage2D (GLenum target, GLint level, GLint xoffset, GLint yoffset, GLint x, GLint y, GLsizei width, GLsizei height); |
||||
GL_APICALL GLuint GL_APIENTRY glCreateProgram (void); |
||||
GL_APICALL GLuint GL_APIENTRY glCreateShader (GLenum type); |
||||
GL_APICALL void GL_APIENTRY glCullFace (GLenum mode); |
||||
GL_APICALL void GL_APIENTRY glDeleteBuffers (GLsizei n, const GLuint* buffers); |
||||
GL_APICALL void GL_APIENTRY glDeleteFramebuffers (GLsizei n, const GLuint* framebuffers); |
||||
GL_APICALL void GL_APIENTRY glDeleteProgram (GLuint program); |
||||
GL_APICALL void GL_APIENTRY glDeleteRenderbuffers (GLsizei n, const GLuint* renderbuffers); |
||||
GL_APICALL void GL_APIENTRY glDeleteShader (GLuint shader); |
||||
GL_APICALL void GL_APIENTRY glDeleteTextures (GLsizei n, const GLuint* textures); |
||||
GL_APICALL void GL_APIENTRY glDepthFunc (GLenum func); |
||||
GL_APICALL void GL_APIENTRY glDepthMask (GLboolean flag); |
||||
GL_APICALL void GL_APIENTRY glDepthRangef (GLclampf zNear, GLclampf zFar); |
||||
GL_APICALL void GL_APIENTRY glDetachShader (GLuint program, GLuint shader); |
||||
GL_APICALL void GL_APIENTRY glDisable (GLenum cap); |
||||
GL_APICALL void GL_APIENTRY glDisableVertexAttribArray (GLuint index); |
||||
GL_APICALL void GL_APIENTRY glDrawArrays (GLenum mode, GLint first, GLsizei count); |
||||
GL_APICALL void GL_APIENTRY glDrawElements (GLenum mode, GLsizei count, GLenum type, const GLvoid* indices); |
||||
GL_APICALL void GL_APIENTRY glEnable (GLenum cap); |
||||
GL_APICALL void GL_APIENTRY glEnableVertexAttribArray (GLuint index); |
||||
GL_APICALL void GL_APIENTRY glFinish (void); |
||||
GL_APICALL void GL_APIENTRY glFlush (void); |
||||
GL_APICALL void GL_APIENTRY glFramebufferRenderbuffer (GLenum target, GLenum attachment, GLenum renderbuffertarget, GLuint renderbuffer); |
||||
GL_APICALL void GL_APIENTRY glFramebufferTexture2D (GLenum target, GLenum attachment, GLenum textarget, GLuint texture, GLint level); |
||||
GL_APICALL void GL_APIENTRY glFrontFace (GLenum mode); |
||||
GL_APICALL void GL_APIENTRY glGenBuffers (GLsizei n, GLuint* buffers); |
||||
GL_APICALL void GL_APIENTRY glGenerateMipmap (GLenum target); |
||||
GL_APICALL void GL_APIENTRY glGenFramebuffers (GLsizei n, GLuint* framebuffers); |
||||
GL_APICALL void GL_APIENTRY glGenRenderbuffers (GLsizei n, GLuint* renderbuffers); |
||||
GL_APICALL void GL_APIENTRY glGenTextures (GLsizei n, GLuint* textures); |
||||
GL_APICALL void GL_APIENTRY glGetActiveAttrib (GLuint program, GLuint index, GLsizei bufsize, GLsizei* length, GLint* size, GLenum* type, GLchar* name); |
||||
GL_APICALL void GL_APIENTRY glGetActiveUniform (GLuint program, GLuint index, GLsizei bufsize, GLsizei* length, GLint* size, GLenum* type, GLchar* name); |
||||
GL_APICALL void GL_APIENTRY glGetAttachedShaders (GLuint program, GLsizei maxcount, GLsizei* count, GLuint* shaders); |
||||
GL_APICALL GLint GL_APIENTRY glGetAttribLocation (GLuint program, const GLchar* name); |
||||
GL_APICALL void GL_APIENTRY glGetBooleanv (GLenum pname, GLboolean* params); |
||||
GL_APICALL void GL_APIENTRY glGetBufferParameteriv (GLenum target, GLenum pname, GLint* params); |
||||
GL_APICALL GLenum GL_APIENTRY glGetError (void); |
||||
GL_APICALL void GL_APIENTRY glGetFloatv (GLenum pname, GLfloat* params); |
||||
GL_APICALL void GL_APIENTRY glGetFramebufferAttachmentParameteriv (GLenum target, GLenum attachment, GLenum pname, GLint* params); |
||||
GL_APICALL void GL_APIENTRY glGetIntegerv (GLenum pname, GLint* params); |
||||
GL_APICALL void GL_APIENTRY glGetProgramiv (GLuint program, GLenum pname, GLint* params); |
||||
GL_APICALL void GL_APIENTRY glGetProgramInfoLog (GLuint program, GLsizei bufsize, GLsizei* length, GLchar* infolog); |
||||
GL_APICALL void GL_APIENTRY glGetRenderbufferParameteriv (GLenum target, GLenum pname, GLint* params); |
||||
GL_APICALL void GL_APIENTRY glGetShaderiv (GLuint shader, GLenum pname, GLint* params); |
||||
GL_APICALL void GL_APIENTRY glGetShaderInfoLog (GLuint shader, GLsizei bufsize, GLsizei* length, GLchar* infolog); |
||||
GL_APICALL void GL_APIENTRY glGetShaderPrecisionFormat (GLenum shadertype, GLenum precisiontype, GLint* range, GLint* precision); |
||||
GL_APICALL void GL_APIENTRY glGetShaderSource (GLuint shader, GLsizei bufsize, GLsizei* length, GLchar* source); |
||||
GL_APICALL const GLubyte* GL_APIENTRY glGetString (GLenum name); |
||||
GL_APICALL void GL_APIENTRY glGetTexParameterfv (GLenum target, GLenum pname, GLfloat* params); |
||||
GL_APICALL void GL_APIENTRY glGetTexParameteriv (GLenum target, GLenum pname, GLint* params); |
||||
GL_APICALL void GL_APIENTRY glGetUniformfv (GLuint program, GLint location, GLfloat* params); |
||||
GL_APICALL void GL_APIENTRY glGetUniformiv (GLuint program, GLint location, GLint* params); |
||||
GL_APICALL GLint GL_APIENTRY glGetUniformLocation (GLuint program, const GLchar* name); |
||||
GL_APICALL void GL_APIENTRY glGetVertexAttribfv (GLuint index, GLenum pname, GLfloat* params); |
||||
GL_APICALL void GL_APIENTRY glGetVertexAttribiv (GLuint index, GLenum pname, GLint* params); |
||||
GL_APICALL void GL_APIENTRY glGetVertexAttribPointerv (GLuint index, GLenum pname, GLvoid** pointer); |
||||
GL_APICALL void GL_APIENTRY glHint (GLenum target, GLenum mode); |
||||
GL_APICALL GLboolean GL_APIENTRY glIsBuffer (GLuint buffer); |
||||
GL_APICALL GLboolean GL_APIENTRY glIsEnabled (GLenum cap); |
||||
GL_APICALL GLboolean GL_APIENTRY glIsFramebuffer (GLuint framebuffer); |
||||
GL_APICALL GLboolean GL_APIENTRY glIsProgram (GLuint program); |
||||
GL_APICALL GLboolean GL_APIENTRY glIsRenderbuffer (GLuint renderbuffer); |
||||
GL_APICALL GLboolean GL_APIENTRY glIsShader (GLuint shader); |
||||
GL_APICALL GLboolean GL_APIENTRY glIsTexture (GLuint texture); |
||||
GL_APICALL void GL_APIENTRY glLineWidth (GLfloat width); |
||||
GL_APICALL void GL_APIENTRY glLinkProgram (GLuint program); |
||||
GL_APICALL void GL_APIENTRY glPixelStorei (GLenum pname, GLint param); |
||||
GL_APICALL void GL_APIENTRY glPolygonOffset (GLfloat factor, GLfloat units); |
||||
GL_APICALL void GL_APIENTRY glReadPixels (GLint x, GLint y, GLsizei width, GLsizei height, GLenum format, GLenum type, GLvoid* pixels); |
||||
GL_APICALL void GL_APIENTRY glReleaseShaderCompiler (void); |
||||
GL_APICALL void GL_APIENTRY glRenderbufferStorage (GLenum target, GLenum internalformat, GLsizei width, GLsizei height); |
||||
GL_APICALL void GL_APIENTRY glSampleCoverage (GLclampf value, GLboolean invert); |
||||
GL_APICALL void GL_APIENTRY glScissor (GLint x, GLint y, GLsizei width, GLsizei height); |
||||
GL_APICALL void GL_APIENTRY glShaderBinary (GLsizei n, const GLuint* shaders, GLenum binaryformat, const GLvoid* binary, GLsizei length); |
||||
GL_APICALL void GL_APIENTRY glShaderSource (GLuint shader, GLsizei count, const GLchar* const* string, const GLint* length); |
||||
GL_APICALL void GL_APIENTRY glStencilFunc (GLenum func, GLint ref, GLuint mask); |
||||
GL_APICALL void GL_APIENTRY glStencilFuncSeparate (GLenum face, GLenum func, GLint ref, GLuint mask); |
||||
GL_APICALL void GL_APIENTRY glStencilMask (GLuint mask); |
||||
GL_APICALL void GL_APIENTRY glStencilMaskSeparate (GLenum face, GLuint mask); |
||||
GL_APICALL void GL_APIENTRY glStencilOp (GLenum fail, GLenum zfail, GLenum zpass); |
||||
GL_APICALL void GL_APIENTRY glStencilOpSeparate (GLenum face, GLenum fail, GLenum zfail, GLenum zpass); |
||||
GL_APICALL void GL_APIENTRY glTexImage2D (GLenum target, GLint level, GLint internalformat, GLsizei width, GLsizei height, GLint border, GLenum format, GLenum type, const GLvoid* pixels); |
||||
GL_APICALL void GL_APIENTRY glTexParameterf (GLenum target, GLenum pname, GLfloat param); |
||||
GL_APICALL void GL_APIENTRY glTexParameterfv (GLenum target, GLenum pname, const GLfloat* params); |
||||
GL_APICALL void GL_APIENTRY glTexParameteri (GLenum target, GLenum pname, GLint param); |
||||
GL_APICALL void GL_APIENTRY glTexParameteriv (GLenum target, GLenum pname, const GLint* params); |
||||
GL_APICALL void GL_APIENTRY glTexSubImage2D (GLenum target, GLint level, GLint xoffset, GLint yoffset, GLsizei width, GLsizei height, GLenum format, GLenum type, const GLvoid* pixels); |
||||
GL_APICALL void GL_APIENTRY glUniform1f (GLint location, GLfloat x); |
||||
GL_APICALL void GL_APIENTRY glUniform1fv (GLint location, GLsizei count, const GLfloat* v); |
||||
GL_APICALL void GL_APIENTRY glUniform1i (GLint location, GLint x); |
||||
GL_APICALL void GL_APIENTRY glUniform1iv (GLint location, GLsizei count, const GLint* v); |
||||
GL_APICALL void GL_APIENTRY glUniform2f (GLint location, GLfloat x, GLfloat y); |
||||
GL_APICALL void GL_APIENTRY glUniform2fv (GLint location, GLsizei count, const GLfloat* v); |
||||
GL_APICALL void GL_APIENTRY glUniform2i (GLint location, GLint x, GLint y); |
||||
GL_APICALL void GL_APIENTRY glUniform2iv (GLint location, GLsizei count, const GLint* v); |
||||
GL_APICALL void GL_APIENTRY glUniform3f (GLint location, GLfloat x, GLfloat y, GLfloat z); |
||||
GL_APICALL void GL_APIENTRY glUniform3fv (GLint location, GLsizei count, const GLfloat* v); |
||||
GL_APICALL void GL_APIENTRY glUniform3i (GLint location, GLint x, GLint y, GLint z); |
||||
GL_APICALL void GL_APIENTRY glUniform3iv (GLint location, GLsizei count, const GLint* v); |
||||
GL_APICALL void GL_APIENTRY glUniform4f (GLint location, GLfloat x, GLfloat y, GLfloat z, GLfloat w); |
||||
GL_APICALL void GL_APIENTRY glUniform4fv (GLint location, GLsizei count, const GLfloat* v); |
||||
GL_APICALL void GL_APIENTRY glUniform4i (GLint location, GLint x, GLint y, GLint z, GLint w); |
||||
GL_APICALL void GL_APIENTRY glUniform4iv (GLint location, GLsizei count, const GLint* v); |
||||
GL_APICALL void GL_APIENTRY glUniformMatrix2fv (GLint location, GLsizei count, GLboolean transpose, const GLfloat* value); |
||||
GL_APICALL void GL_APIENTRY glUniformMatrix3fv (GLint location, GLsizei count, GLboolean transpose, const GLfloat* value); |
||||
GL_APICALL void GL_APIENTRY glUniformMatrix4fv (GLint location, GLsizei count, GLboolean transpose, const GLfloat* value); |
||||
GL_APICALL void GL_APIENTRY glUseProgram (GLuint program); |
||||
GL_APICALL void GL_APIENTRY glValidateProgram (GLuint program); |
||||
GL_APICALL void GL_APIENTRY glVertexAttrib1f (GLuint indx, GLfloat x); |
||||
GL_APICALL void GL_APIENTRY glVertexAttrib1fv (GLuint indx, const GLfloat* values); |
||||
GL_APICALL void GL_APIENTRY glVertexAttrib2f (GLuint indx, GLfloat x, GLfloat y); |
||||
GL_APICALL void GL_APIENTRY glVertexAttrib2fv (GLuint indx, const GLfloat* values); |
||||
GL_APICALL void GL_APIENTRY glVertexAttrib3f (GLuint indx, GLfloat x, GLfloat y, GLfloat z); |
||||
GL_APICALL void GL_APIENTRY glVertexAttrib3fv (GLuint indx, const GLfloat* values); |
||||
GL_APICALL void GL_APIENTRY glVertexAttrib4f (GLuint indx, GLfloat x, GLfloat y, GLfloat z, GLfloat w); |
||||
GL_APICALL void GL_APIENTRY glVertexAttrib4fv (GLuint indx, const GLfloat* values); |
||||
GL_APICALL void GL_APIENTRY glVertexAttribPointer (GLuint indx, GLint size, GLenum type, GLboolean normalized, GLsizei stride, const GLvoid* ptr); |
||||
GL_APICALL void GL_APIENTRY glViewport (GLint x, GLint y, GLsizei width, GLsizei height); |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif /* __gl2_h_ */ |
||||
|
||||
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,30 @@ |
||||
#ifndef __gl2platform_h_ |
||||
#define __gl2platform_h_ |
||||
|
||||
/* $Revision: 10602 $ on $Date:: 2010-03-04 22:35:34 -0800 #$ */ |
||||
|
||||
/*
|
||||
* This document is licensed under the SGI Free Software B License Version |
||||
* 2.0. For details, see http://oss.sgi.com/projects/FreeB/ .
|
||||
*/ |
||||
|
||||
/* Platform-specific types and definitions for OpenGL ES 2.X gl2.h
|
||||
* |
||||
* Adopters may modify khrplatform.h and this file to suit their platform. |
||||
* You are encouraged to submit all modifications to the Khronos group so that |
||||
* they can be included in future versions of this file. Please submit changes |
||||
* by sending them to the public Khronos Bugzilla (http://khronos.org/bugzilla)
|
||||
* by filing a bug against product "OpenGL-ES" component "Registry". |
||||
*/ |
||||
|
||||
/*#include <KHR/khrplatform.h>*/ |
||||
|
||||
#ifndef GL_APICALL |
||||
#define GL_APICALL KHRONOS_APICALL |
||||
#endif |
||||
|
||||
#ifndef GL_APIENTRY |
||||
#define GL_APIENTRY KHRONOS_APIENTRY |
||||
#endif |
||||
|
||||
#endif /* __gl2platform_h_ */ |
||||
@ -0,0 +1,282 @@ |
||||
#ifndef __khrplatform_h_ |
||||
#define __khrplatform_h_ |
||||
|
||||
/*
|
||||
** Copyright (c) 2008-2009 The Khronos Group Inc. |
||||
** |
||||
** Permission is hereby granted, free of charge, to any person obtaining a |
||||
** copy of this software and/or associated documentation files (the |
||||
** "Materials"), to deal in the Materials without restriction, including |
||||
** without limitation the rights to use, copy, modify, merge, publish, |
||||
** distribute, sublicense, and/or sell copies of the Materials, and to |
||||
** permit persons to whom the Materials are furnished to do so, subject to |
||||
** the following conditions: |
||||
** |
||||
** The above copyright notice and this permission notice shall be included |
||||
** in all copies or substantial portions of the Materials. |
||||
** |
||||
** THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, |
||||
** EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF |
||||
** MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. |
||||
** IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY |
||||
** CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, |
||||
** TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE |
||||
** MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. |
||||
*/ |
||||
|
||||
/* Khronos platform-specific types and definitions.
|
||||
* |
||||
* $Revision: 23298 $ on $Date: 2013-09-30 17:07:13 -0700 (Mon, 30 Sep 2013) $ |
||||
* |
||||
* Adopters may modify this file to suit their platform. Adopters are |
||||
* encouraged to submit platform specific modifications to the Khronos |
||||
* group so that they can be included in future versions of this file. |
||||
* Please submit changes by sending them to the public Khronos Bugzilla |
||||
* (http://khronos.org/bugzilla) by filing a bug against product
|
||||
* "Khronos (general)" component "Registry". |
||||
* |
||||
* A predefined template which fills in some of the bug fields can be |
||||
* reached using http://tinyurl.com/khrplatform-h-bugreport, but you
|
||||
* must create a Bugzilla login first. |
||||
* |
||||
* |
||||
* See the Implementer's Guidelines for information about where this file |
||||
* should be located on your system and for more details of its use: |
||||
* http://www.khronos.org/registry/implementers_guide.pdf
|
||||
* |
||||
* This file should be included as |
||||
* #include <KHR/khrplatform.h> |
||||
* by Khronos client API header files that use its types and defines. |
||||
* |
||||
* The types in khrplatform.h should only be used to define API-specific types. |
||||
* |
||||
* Types defined in khrplatform.h: |
||||
* khronos_int8_t signed 8 bit |
||||
* khronos_uint8_t unsigned 8 bit |
||||
* khronos_int16_t signed 16 bit |
||||
* khronos_uint16_t unsigned 16 bit |
||||
* khronos_int32_t signed 32 bit |
||||
* khronos_uint32_t unsigned 32 bit |
||||
* khronos_int64_t signed 64 bit |
||||
* khronos_uint64_t unsigned 64 bit |
||||
* khronos_intptr_t signed same number of bits as a pointer |
||||
* khronos_uintptr_t unsigned same number of bits as a pointer |
||||
* khronos_ssize_t signed size |
||||
* khronos_usize_t unsigned size |
||||
* khronos_float_t signed 32 bit floating point |
||||
* khronos_time_ns_t unsigned 64 bit time in nanoseconds |
||||
* khronos_utime_nanoseconds_t unsigned time interval or absolute time in |
||||
* nanoseconds |
||||
* khronos_stime_nanoseconds_t signed time interval in nanoseconds |
||||
* khronos_boolean_enum_t enumerated boolean type. This should |
||||
* only be used as a base type when a client API's boolean type is |
||||
* an enum. Client APIs which use an integer or other type for |
||||
* booleans cannot use this as the base type for their boolean. |
||||
* |
||||
* Tokens defined in khrplatform.h: |
||||
* |
||||
* KHRONOS_FALSE, KHRONOS_TRUE Enumerated boolean false/true values. |
||||
* |
||||
* KHRONOS_SUPPORT_INT64 is 1 if 64 bit integers are supported; otherwise 0. |
||||
* KHRONOS_SUPPORT_FLOAT is 1 if floats are supported; otherwise 0. |
||||
* |
||||
* Calling convention macros defined in this file: |
||||
* KHRONOS_APICALL |
||||
* KHRONOS_APIENTRY |
||||
* KHRONOS_APIATTRIBUTES |
||||
* |
||||
* These may be used in function prototypes as: |
||||
* |
||||
* KHRONOS_APICALL void KHRONOS_APIENTRY funcname( |
||||
* int arg1, |
||||
* int arg2) KHRONOS_APIATTRIBUTES; |
||||
*/ |
||||
|
||||
/*-------------------------------------------------------------------------
|
||||
* Definition of KHRONOS_APICALL |
||||
*------------------------------------------------------------------------- |
||||
* This precedes the return type of the function in the function prototype. |
||||
*/ |
||||
#if defined(_WIN32) && !defined(__SCITECH_SNAP__) |
||||
# define KHRONOS_APICALL __declspec(dllimport) |
||||
#elif defined (__SYMBIAN32__) |
||||
# define KHRONOS_APICALL IMPORT_C |
||||
#else |
||||
# define KHRONOS_APICALL |
||||
#endif |
||||
|
||||
/*-------------------------------------------------------------------------
|
||||
* Definition of KHRONOS_APIENTRY |
||||
*------------------------------------------------------------------------- |
||||
* This follows the return type of the function and precedes the function |
||||
* name in the function prototype. |
||||
*/ |
||||
#if defined(_WIN32) && !defined(_WIN32_WCE) && !defined(__SCITECH_SNAP__) |
||||
/* Win32 but not WinCE */ |
||||
# define KHRONOS_APIENTRY __stdcall |
||||
#else |
||||
# define KHRONOS_APIENTRY |
||||
#endif |
||||
|
||||
/*-------------------------------------------------------------------------
|
||||
* Definition of KHRONOS_APIATTRIBUTES |
||||
*------------------------------------------------------------------------- |
||||
* This follows the closing parenthesis of the function prototype arguments. |
||||
*/ |
||||
#if defined (__ARMCC_2__) |
||||
#define KHRONOS_APIATTRIBUTES __softfp |
||||
#else |
||||
#define KHRONOS_APIATTRIBUTES |
||||
#endif |
||||
|
||||
/*-------------------------------------------------------------------------
|
||||
* basic type definitions |
||||
*-----------------------------------------------------------------------*/ |
||||
#if (defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L) || defined(__GNUC__) || defined(__SCO__) || defined(__USLC__) |
||||
|
||||
|
||||
/*
|
||||
* Using <stdint.h> |
||||
*/ |
||||
#include <stdint.h> |
||||
typedef int32_t khronos_int32_t; |
||||
typedef uint32_t khronos_uint32_t; |
||||
typedef int64_t khronos_int64_t; |
||||
typedef uint64_t khronos_uint64_t; |
||||
#define KHRONOS_SUPPORT_INT64 1 |
||||
#define KHRONOS_SUPPORT_FLOAT 1 |
||||
|
||||
#elif defined(__VMS ) || defined(__sgi) |
||||
|
||||
/*
|
||||
* Using <inttypes.h> |
||||
*/ |
||||
#include <inttypes.h> |
||||
typedef int32_t khronos_int32_t; |
||||
typedef uint32_t khronos_uint32_t; |
||||
typedef int64_t khronos_int64_t; |
||||
typedef uint64_t khronos_uint64_t; |
||||
#define KHRONOS_SUPPORT_INT64 1 |
||||
#define KHRONOS_SUPPORT_FLOAT 1 |
||||
|
||||
#elif defined(_WIN32) && !defined(__SCITECH_SNAP__) |
||||
|
||||
/*
|
||||
* Win32 |
||||
*/ |
||||
typedef __int32 khronos_int32_t; |
||||
typedef unsigned __int32 khronos_uint32_t; |
||||
typedef __int64 khronos_int64_t; |
||||
typedef unsigned __int64 khronos_uint64_t; |
||||
#define KHRONOS_SUPPORT_INT64 1 |
||||
#define KHRONOS_SUPPORT_FLOAT 1 |
||||
|
||||
#elif defined(__sun__) || defined(__digital__) |
||||
|
||||
/*
|
||||
* Sun or Digital |
||||
*/ |
||||
typedef int khronos_int32_t; |
||||
typedef unsigned int khronos_uint32_t; |
||||
#if defined(__arch64__) || defined(_LP64) |
||||
typedef long int khronos_int64_t; |
||||
typedef unsigned long int khronos_uint64_t; |
||||
#else |
||||
typedef long long int khronos_int64_t; |
||||
typedef unsigned long long int khronos_uint64_t; |
||||
#endif /* __arch64__ */ |
||||
#define KHRONOS_SUPPORT_INT64 1 |
||||
#define KHRONOS_SUPPORT_FLOAT 1 |
||||
|
||||
#elif 0 |
||||
|
||||
/*
|
||||
* Hypothetical platform with no float or int64 support |
||||
*/ |
||||
typedef int khronos_int32_t; |
||||
typedef unsigned int khronos_uint32_t; |
||||
#define KHRONOS_SUPPORT_INT64 0 |
||||
#define KHRONOS_SUPPORT_FLOAT 0 |
||||
|
||||
#else |
||||
|
||||
/*
|
||||
* Generic fallback |
||||
*/ |
||||
#include <stdint.h> |
||||
typedef int32_t khronos_int32_t; |
||||
typedef uint32_t khronos_uint32_t; |
||||
typedef int64_t khronos_int64_t; |
||||
typedef uint64_t khronos_uint64_t; |
||||
#define KHRONOS_SUPPORT_INT64 1 |
||||
#define KHRONOS_SUPPORT_FLOAT 1 |
||||
|
||||
#endif |
||||
|
||||
|
||||
/*
|
||||
* Types that are (so far) the same on all platforms |
||||
*/ |
||||
typedef signed char khronos_int8_t; |
||||
typedef unsigned char khronos_uint8_t; |
||||
typedef signed short int khronos_int16_t; |
||||
typedef unsigned short int khronos_uint16_t; |
||||
|
||||
/*
|
||||
* Types that differ between LLP64 and LP64 architectures - in LLP64,
|
||||
* pointers are 64 bits, but 'long' is still 32 bits. Win64 appears |
||||
* to be the only LLP64 architecture in current use. |
||||
*/ |
||||
#ifdef _WIN64 |
||||
typedef signed long long int khronos_intptr_t; |
||||
typedef unsigned long long int khronos_uintptr_t; |
||||
typedef signed long long int khronos_ssize_t; |
||||
typedef unsigned long long int khronos_usize_t; |
||||
#else |
||||
typedef signed long int khronos_intptr_t; |
||||
typedef unsigned long int khronos_uintptr_t; |
||||
typedef signed long int khronos_ssize_t; |
||||
typedef unsigned long int khronos_usize_t; |
||||
#endif |
||||
|
||||
#if KHRONOS_SUPPORT_FLOAT |
||||
/*
|
||||
* Float type |
||||
*/ |
||||
typedef float khronos_float_t; |
||||
#endif |
||||
|
||||
#if KHRONOS_SUPPORT_INT64 |
||||
/* Time types
|
||||
* |
||||
* These types can be used to represent a time interval in nanoseconds or |
||||
* an absolute Unadjusted System Time. Unadjusted System Time is the number |
||||
* of nanoseconds since some arbitrary system event (e.g. since the last |
||||
* time the system booted). The Unadjusted System Time is an unsigned |
||||
* 64 bit value that wraps back to 0 every 584 years. Time intervals |
||||
* may be either signed or unsigned. |
||||
*/ |
||||
typedef khronos_uint64_t khronos_utime_nanoseconds_t; |
||||
typedef khronos_int64_t khronos_stime_nanoseconds_t; |
||||
#endif |
||||
|
||||
/*
|
||||
* Dummy value used to pad enum types to 32 bits. |
||||
*/ |
||||
#ifndef KHRONOS_MAX_ENUM |
||||
#define KHRONOS_MAX_ENUM 0x7FFFFFFF |
||||
#endif |
||||
|
||||
/*
|
||||
* Enumerated boolean type |
||||
* |
||||
* Values other than zero should be considered to be true. Therefore |
||||
* comparisons should not be made against KHRONOS_TRUE. |
||||
*/ |
||||
typedef enum { |
||||
KHRONOS_FALSE = 0, |
||||
KHRONOS_TRUE = 1, |
||||
KHRONOS_BOOLEAN_ENUM_FORCE_SIZE = KHRONOS_MAX_ENUM |
||||
} khronos_boolean_enum_t; |
||||
|
||||
#endif /* __khrplatform_h_ */ |
||||
@ -0,0 +1,470 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_pixels.h |
||||
* |
||||
* Header for the enumerated pixel format definitions. |
||||
*/ |
||||
|
||||
#ifndef SDL_pixels_h_ |
||||
#define SDL_pixels_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_endian.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \name Transparency definitions |
||||
* |
||||
* These define alpha as the opacity of a surface. |
||||
*/ |
||||
/* @{ */ |
||||
#define SDL_ALPHA_OPAQUE 255 |
||||
#define SDL_ALPHA_TRANSPARENT 0 |
||||
/* @} */ |
||||
|
||||
/** Pixel type. */ |
||||
enum |
||||
{ |
||||
SDL_PIXELTYPE_UNKNOWN, |
||||
SDL_PIXELTYPE_INDEX1, |
||||
SDL_PIXELTYPE_INDEX4, |
||||
SDL_PIXELTYPE_INDEX8, |
||||
SDL_PIXELTYPE_PACKED8, |
||||
SDL_PIXELTYPE_PACKED16, |
||||
SDL_PIXELTYPE_PACKED32, |
||||
SDL_PIXELTYPE_ARRAYU8, |
||||
SDL_PIXELTYPE_ARRAYU16, |
||||
SDL_PIXELTYPE_ARRAYU32, |
||||
SDL_PIXELTYPE_ARRAYF16, |
||||
SDL_PIXELTYPE_ARRAYF32 |
||||
}; |
||||
|
||||
/** Bitmap pixel order, high bit -> low bit. */ |
||||
enum |
||||
{ |
||||
SDL_BITMAPORDER_NONE, |
||||
SDL_BITMAPORDER_4321, |
||||
SDL_BITMAPORDER_1234 |
||||
}; |
||||
|
||||
/** Packed component order, high bit -> low bit. */ |
||||
enum |
||||
{ |
||||
SDL_PACKEDORDER_NONE, |
||||
SDL_PACKEDORDER_XRGB, |
||||
SDL_PACKEDORDER_RGBX, |
||||
SDL_PACKEDORDER_ARGB, |
||||
SDL_PACKEDORDER_RGBA, |
||||
SDL_PACKEDORDER_XBGR, |
||||
SDL_PACKEDORDER_BGRX, |
||||
SDL_PACKEDORDER_ABGR, |
||||
SDL_PACKEDORDER_BGRA |
||||
}; |
||||
|
||||
/** Array component order, low byte -> high byte. */ |
||||
/* !!! FIXME: in 2.1, make these not overlap differently with
|
||||
!!! FIXME: SDL_PACKEDORDER_*, so we can simplify SDL_ISPIXELFORMAT_ALPHA */ |
||||
enum |
||||
{ |
||||
SDL_ARRAYORDER_NONE, |
||||
SDL_ARRAYORDER_RGB, |
||||
SDL_ARRAYORDER_RGBA, |
||||
SDL_ARRAYORDER_ARGB, |
||||
SDL_ARRAYORDER_BGR, |
||||
SDL_ARRAYORDER_BGRA, |
||||
SDL_ARRAYORDER_ABGR |
||||
}; |
||||
|
||||
/** Packed component layout. */ |
||||
enum |
||||
{ |
||||
SDL_PACKEDLAYOUT_NONE, |
||||
SDL_PACKEDLAYOUT_332, |
||||
SDL_PACKEDLAYOUT_4444, |
||||
SDL_PACKEDLAYOUT_1555, |
||||
SDL_PACKEDLAYOUT_5551, |
||||
SDL_PACKEDLAYOUT_565, |
||||
SDL_PACKEDLAYOUT_8888, |
||||
SDL_PACKEDLAYOUT_2101010, |
||||
SDL_PACKEDLAYOUT_1010102 |
||||
}; |
||||
|
||||
#define SDL_DEFINE_PIXELFOURCC(A, B, C, D) SDL_FOURCC(A, B, C, D) |
||||
|
||||
#define SDL_DEFINE_PIXELFORMAT(type, order, layout, bits, bytes) \ |
||||
((1 << 28) | ((type) << 24) | ((order) << 20) | ((layout) << 16) | \
|
||||
((bits) << 8) | ((bytes) << 0)) |
||||
|
||||
#define SDL_PIXELFLAG(X) (((X) >> 28) & 0x0F) |
||||
#define SDL_PIXELTYPE(X) (((X) >> 24) & 0x0F) |
||||
#define SDL_PIXELORDER(X) (((X) >> 20) & 0x0F) |
||||
#define SDL_PIXELLAYOUT(X) (((X) >> 16) & 0x0F) |
||||
#define SDL_BITSPERPIXEL(X) (((X) >> 8) & 0xFF) |
||||
#define SDL_BYTESPERPIXEL(X) \ |
||||
(SDL_ISPIXELFORMAT_FOURCC(X) ? \
|
||||
((((X) == SDL_PIXELFORMAT_YUY2) || \
|
||||
((X) == SDL_PIXELFORMAT_UYVY) || \
|
||||
((X) == SDL_PIXELFORMAT_YVYU)) ? 2 : 1) : (((X) >> 0) & 0xFF)) |
||||
|
||||
#define SDL_ISPIXELFORMAT_INDEXED(format) \ |
||||
(!SDL_ISPIXELFORMAT_FOURCC(format) && \
|
||||
((SDL_PIXELTYPE(format) == SDL_PIXELTYPE_INDEX1) || \
|
||||
(SDL_PIXELTYPE(format) == SDL_PIXELTYPE_INDEX4) || \
|
||||
(SDL_PIXELTYPE(format) == SDL_PIXELTYPE_INDEX8))) |
||||
|
||||
#define SDL_ISPIXELFORMAT_PACKED(format) \ |
||||
(!SDL_ISPIXELFORMAT_FOURCC(format) && \
|
||||
((SDL_PIXELTYPE(format) == SDL_PIXELTYPE_PACKED8) || \
|
||||
(SDL_PIXELTYPE(format) == SDL_PIXELTYPE_PACKED16) || \
|
||||
(SDL_PIXELTYPE(format) == SDL_PIXELTYPE_PACKED32))) |
||||
|
||||
#define SDL_ISPIXELFORMAT_ARRAY(format) \ |
||||
(!SDL_ISPIXELFORMAT_FOURCC(format) && \
|
||||
((SDL_PIXELTYPE(format) == SDL_PIXELTYPE_ARRAYU8) || \
|
||||
(SDL_PIXELTYPE(format) == SDL_PIXELTYPE_ARRAYU16) || \
|
||||
(SDL_PIXELTYPE(format) == SDL_PIXELTYPE_ARRAYU32) || \
|
||||
(SDL_PIXELTYPE(format) == SDL_PIXELTYPE_ARRAYF16) || \
|
||||
(SDL_PIXELTYPE(format) == SDL_PIXELTYPE_ARRAYF32))) |
||||
|
||||
#define SDL_ISPIXELFORMAT_ALPHA(format) \ |
||||
((SDL_ISPIXELFORMAT_PACKED(format) && \
|
||||
((SDL_PIXELORDER(format) == SDL_PACKEDORDER_ARGB) || \
|
||||
(SDL_PIXELORDER(format) == SDL_PACKEDORDER_RGBA) || \
|
||||
(SDL_PIXELORDER(format) == SDL_PACKEDORDER_ABGR) || \
|
||||
(SDL_PIXELORDER(format) == SDL_PACKEDORDER_BGRA))) || \
|
||||
(SDL_ISPIXELFORMAT_ARRAY(format) && \
|
||||
((SDL_PIXELORDER(format) == SDL_ARRAYORDER_ARGB) || \
|
||||
(SDL_PIXELORDER(format) == SDL_ARRAYORDER_RGBA) || \
|
||||
(SDL_PIXELORDER(format) == SDL_ARRAYORDER_ABGR) || \
|
||||
(SDL_PIXELORDER(format) == SDL_ARRAYORDER_BGRA)))) |
||||
|
||||
/* The flag is set to 1 because 0x1? is not in the printable ASCII range */ |
||||
#define SDL_ISPIXELFORMAT_FOURCC(format) \ |
||||
((format) && (SDL_PIXELFLAG(format) != 1)) |
||||
|
||||
/* Note: If you modify this list, update SDL_GetPixelFormatName() */ |
||||
typedef enum |
||||
{ |
||||
SDL_PIXELFORMAT_UNKNOWN, |
||||
SDL_PIXELFORMAT_INDEX1LSB = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_INDEX1, SDL_BITMAPORDER_4321, 0, |
||||
1, 0), |
||||
SDL_PIXELFORMAT_INDEX1MSB = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_INDEX1, SDL_BITMAPORDER_1234, 0, |
||||
1, 0), |
||||
SDL_PIXELFORMAT_INDEX4LSB = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_INDEX4, SDL_BITMAPORDER_4321, 0, |
||||
4, 0), |
||||
SDL_PIXELFORMAT_INDEX4MSB = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_INDEX4, SDL_BITMAPORDER_1234, 0, |
||||
4, 0), |
||||
SDL_PIXELFORMAT_INDEX8 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_INDEX8, 0, 0, 8, 1), |
||||
SDL_PIXELFORMAT_RGB332 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED8, SDL_PACKEDORDER_XRGB, |
||||
SDL_PACKEDLAYOUT_332, 8, 1), |
||||
SDL_PIXELFORMAT_RGB444 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_XRGB, |
||||
SDL_PACKEDLAYOUT_4444, 12, 2), |
||||
SDL_PIXELFORMAT_RGB555 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_XRGB, |
||||
SDL_PACKEDLAYOUT_1555, 15, 2), |
||||
SDL_PIXELFORMAT_BGR555 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_XBGR, |
||||
SDL_PACKEDLAYOUT_1555, 15, 2), |
||||
SDL_PIXELFORMAT_ARGB4444 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_ARGB, |
||||
SDL_PACKEDLAYOUT_4444, 16, 2), |
||||
SDL_PIXELFORMAT_RGBA4444 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_RGBA, |
||||
SDL_PACKEDLAYOUT_4444, 16, 2), |
||||
SDL_PIXELFORMAT_ABGR4444 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_ABGR, |
||||
SDL_PACKEDLAYOUT_4444, 16, 2), |
||||
SDL_PIXELFORMAT_BGRA4444 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_BGRA, |
||||
SDL_PACKEDLAYOUT_4444, 16, 2), |
||||
SDL_PIXELFORMAT_ARGB1555 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_ARGB, |
||||
SDL_PACKEDLAYOUT_1555, 16, 2), |
||||
SDL_PIXELFORMAT_RGBA5551 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_RGBA, |
||||
SDL_PACKEDLAYOUT_5551, 16, 2), |
||||
SDL_PIXELFORMAT_ABGR1555 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_ABGR, |
||||
SDL_PACKEDLAYOUT_1555, 16, 2), |
||||
SDL_PIXELFORMAT_BGRA5551 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_BGRA, |
||||
SDL_PACKEDLAYOUT_5551, 16, 2), |
||||
SDL_PIXELFORMAT_RGB565 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_XRGB, |
||||
SDL_PACKEDLAYOUT_565, 16, 2), |
||||
SDL_PIXELFORMAT_BGR565 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED16, SDL_PACKEDORDER_XBGR, |
||||
SDL_PACKEDLAYOUT_565, 16, 2), |
||||
SDL_PIXELFORMAT_RGB24 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_ARRAYU8, SDL_ARRAYORDER_RGB, 0, |
||||
24, 3), |
||||
SDL_PIXELFORMAT_BGR24 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_ARRAYU8, SDL_ARRAYORDER_BGR, 0, |
||||
24, 3), |
||||
SDL_PIXELFORMAT_RGB888 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED32, SDL_PACKEDORDER_XRGB, |
||||
SDL_PACKEDLAYOUT_8888, 24, 4), |
||||
SDL_PIXELFORMAT_RGBX8888 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED32, SDL_PACKEDORDER_RGBX, |
||||
SDL_PACKEDLAYOUT_8888, 24, 4), |
||||
SDL_PIXELFORMAT_BGR888 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED32, SDL_PACKEDORDER_XBGR, |
||||
SDL_PACKEDLAYOUT_8888, 24, 4), |
||||
SDL_PIXELFORMAT_BGRX8888 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED32, SDL_PACKEDORDER_BGRX, |
||||
SDL_PACKEDLAYOUT_8888, 24, 4), |
||||
SDL_PIXELFORMAT_ARGB8888 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED32, SDL_PACKEDORDER_ARGB, |
||||
SDL_PACKEDLAYOUT_8888, 32, 4), |
||||
SDL_PIXELFORMAT_RGBA8888 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED32, SDL_PACKEDORDER_RGBA, |
||||
SDL_PACKEDLAYOUT_8888, 32, 4), |
||||
SDL_PIXELFORMAT_ABGR8888 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED32, SDL_PACKEDORDER_ABGR, |
||||
SDL_PACKEDLAYOUT_8888, 32, 4), |
||||
SDL_PIXELFORMAT_BGRA8888 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED32, SDL_PACKEDORDER_BGRA, |
||||
SDL_PACKEDLAYOUT_8888, 32, 4), |
||||
SDL_PIXELFORMAT_ARGB2101010 = |
||||
SDL_DEFINE_PIXELFORMAT(SDL_PIXELTYPE_PACKED32, SDL_PACKEDORDER_ARGB, |
||||
SDL_PACKEDLAYOUT_2101010, 32, 4), |
||||
|
||||
/* Aliases for RGBA byte arrays of color data, for the current platform */ |
||||
#if SDL_BYTEORDER == SDL_BIG_ENDIAN |
||||
SDL_PIXELFORMAT_RGBA32 = SDL_PIXELFORMAT_RGBA8888, |
||||
SDL_PIXELFORMAT_ARGB32 = SDL_PIXELFORMAT_ARGB8888, |
||||
SDL_PIXELFORMAT_BGRA32 = SDL_PIXELFORMAT_BGRA8888, |
||||
SDL_PIXELFORMAT_ABGR32 = SDL_PIXELFORMAT_ABGR8888, |
||||
#else |
||||
SDL_PIXELFORMAT_RGBA32 = SDL_PIXELFORMAT_ABGR8888, |
||||
SDL_PIXELFORMAT_ARGB32 = SDL_PIXELFORMAT_BGRA8888, |
||||
SDL_PIXELFORMAT_BGRA32 = SDL_PIXELFORMAT_ARGB8888, |
||||
SDL_PIXELFORMAT_ABGR32 = SDL_PIXELFORMAT_RGBA8888, |
||||
#endif |
||||
|
||||
SDL_PIXELFORMAT_YV12 = /**< Planar mode: Y + V + U (3 planes) */ |
||||
SDL_DEFINE_PIXELFOURCC('Y', 'V', '1', '2'), |
||||
SDL_PIXELFORMAT_IYUV = /**< Planar mode: Y + U + V (3 planes) */ |
||||
SDL_DEFINE_PIXELFOURCC('I', 'Y', 'U', 'V'), |
||||
SDL_PIXELFORMAT_YUY2 = /**< Packed mode: Y0+U0+Y1+V0 (1 plane) */ |
||||
SDL_DEFINE_PIXELFOURCC('Y', 'U', 'Y', '2'), |
||||
SDL_PIXELFORMAT_UYVY = /**< Packed mode: U0+Y0+V0+Y1 (1 plane) */ |
||||
SDL_DEFINE_PIXELFOURCC('U', 'Y', 'V', 'Y'), |
||||
SDL_PIXELFORMAT_YVYU = /**< Packed mode: Y0+V0+Y1+U0 (1 plane) */ |
||||
SDL_DEFINE_PIXELFOURCC('Y', 'V', 'Y', 'U'), |
||||
SDL_PIXELFORMAT_NV12 = /**< Planar mode: Y + U/V interleaved (2 planes) */ |
||||
SDL_DEFINE_PIXELFOURCC('N', 'V', '1', '2'), |
||||
SDL_PIXELFORMAT_NV21 = /**< Planar mode: Y + V/U interleaved (2 planes) */ |
||||
SDL_DEFINE_PIXELFOURCC('N', 'V', '2', '1'), |
||||
SDL_PIXELFORMAT_EXTERNAL_OES = /**< Android video texture format */ |
||||
SDL_DEFINE_PIXELFOURCC('O', 'E', 'S', ' ') |
||||
} SDL_PixelFormatEnum; |
||||
|
||||
typedef struct SDL_Color |
||||
{ |
||||
Uint8 r; |
||||
Uint8 g; |
||||
Uint8 b; |
||||
Uint8 a; |
||||
} SDL_Color; |
||||
#define SDL_Colour SDL_Color |
||||
|
||||
typedef struct SDL_Palette |
||||
{ |
||||
int ncolors; |
||||
SDL_Color *colors; |
||||
Uint32 version; |
||||
int refcount; |
||||
} SDL_Palette; |
||||
|
||||
/**
|
||||
* \note Everything in the pixel format structure is read-only. |
||||
*/ |
||||
typedef struct SDL_PixelFormat |
||||
{ |
||||
Uint32 format; |
||||
SDL_Palette *palette; |
||||
Uint8 BitsPerPixel; |
||||
Uint8 BytesPerPixel; |
||||
Uint8 padding[2]; |
||||
Uint32 Rmask; |
||||
Uint32 Gmask; |
||||
Uint32 Bmask; |
||||
Uint32 Amask; |
||||
Uint8 Rloss; |
||||
Uint8 Gloss; |
||||
Uint8 Bloss; |
||||
Uint8 Aloss; |
||||
Uint8 Rshift; |
||||
Uint8 Gshift; |
||||
Uint8 Bshift; |
||||
Uint8 Ashift; |
||||
int refcount; |
||||
struct SDL_PixelFormat *next; |
||||
} SDL_PixelFormat; |
||||
|
||||
/**
|
||||
* \brief Get the human readable name of a pixel format |
||||
*/ |
||||
extern DECLSPEC const char* SDLCALL SDL_GetPixelFormatName(Uint32 format); |
||||
|
||||
/**
|
||||
* \brief Convert one of the enumerated pixel formats to a bpp and RGBA masks. |
||||
* |
||||
* \return SDL_TRUE, or SDL_FALSE if the conversion wasn't possible. |
||||
* |
||||
* \sa SDL_MasksToPixelFormatEnum() |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_PixelFormatEnumToMasks(Uint32 format, |
||||
int *bpp, |
||||
Uint32 * Rmask, |
||||
Uint32 * Gmask, |
||||
Uint32 * Bmask, |
||||
Uint32 * Amask); |
||||
|
||||
/**
|
||||
* \brief Convert a bpp and RGBA masks to an enumerated pixel format. |
||||
* |
||||
* \return The pixel format, or ::SDL_PIXELFORMAT_UNKNOWN if the conversion |
||||
* wasn't possible. |
||||
* |
||||
* \sa SDL_PixelFormatEnumToMasks() |
||||
*/ |
||||
extern DECLSPEC Uint32 SDLCALL SDL_MasksToPixelFormatEnum(int bpp, |
||||
Uint32 Rmask, |
||||
Uint32 Gmask, |
||||
Uint32 Bmask, |
||||
Uint32 Amask); |
||||
|
||||
/**
|
||||
* \brief Create an SDL_PixelFormat structure from a pixel format enum. |
||||
*/ |
||||
extern DECLSPEC SDL_PixelFormat * SDLCALL SDL_AllocFormat(Uint32 pixel_format); |
||||
|
||||
/**
|
||||
* \brief Free an SDL_PixelFormat structure. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_FreeFormat(SDL_PixelFormat *format); |
||||
|
||||
/**
|
||||
* \brief Create a palette structure with the specified number of color |
||||
* entries. |
||||
* |
||||
* \return A new palette, or NULL if there wasn't enough memory. |
||||
* |
||||
* \note The palette entries are initialized to white. |
||||
* |
||||
* \sa SDL_FreePalette() |
||||
*/ |
||||
extern DECLSPEC SDL_Palette *SDLCALL SDL_AllocPalette(int ncolors); |
||||
|
||||
/**
|
||||
* \brief Set the palette for a pixel format structure. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SetPixelFormatPalette(SDL_PixelFormat * format, |
||||
SDL_Palette *palette); |
||||
|
||||
/**
|
||||
* \brief Set a range of colors in a palette. |
||||
* |
||||
* \param palette The palette to modify. |
||||
* \param colors An array of colors to copy into the palette. |
||||
* \param firstcolor The index of the first palette entry to modify. |
||||
* \param ncolors The number of entries to modify. |
||||
* |
||||
* \return 0 on success, or -1 if not all of the colors could be set. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SetPaletteColors(SDL_Palette * palette, |
||||
const SDL_Color * colors, |
||||
int firstcolor, int ncolors); |
||||
|
||||
/**
|
||||
* \brief Free a palette created with SDL_AllocPalette(). |
||||
* |
||||
* \sa SDL_AllocPalette() |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_FreePalette(SDL_Palette * palette); |
||||
|
||||
/**
|
||||
* \brief Maps an RGB triple to an opaque pixel value for a given pixel format. |
||||
* |
||||
* \sa SDL_MapRGBA |
||||
*/ |
||||
extern DECLSPEC Uint32 SDLCALL SDL_MapRGB(const SDL_PixelFormat * format, |
||||
Uint8 r, Uint8 g, Uint8 b); |
||||
|
||||
/**
|
||||
* \brief Maps an RGBA quadruple to a pixel value for a given pixel format. |
||||
* |
||||
* \sa SDL_MapRGB |
||||
*/ |
||||
extern DECLSPEC Uint32 SDLCALL SDL_MapRGBA(const SDL_PixelFormat * format, |
||||
Uint8 r, Uint8 g, Uint8 b, |
||||
Uint8 a); |
||||
|
||||
/**
|
||||
* \brief Get the RGB components from a pixel of the specified format. |
||||
* |
||||
* \sa SDL_GetRGBA |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_GetRGB(Uint32 pixel, |
||||
const SDL_PixelFormat * format, |
||||
Uint8 * r, Uint8 * g, Uint8 * b); |
||||
|
||||
/**
|
||||
* \brief Get the RGBA components from a pixel of the specified format. |
||||
* |
||||
* \sa SDL_GetRGB |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_GetRGBA(Uint32 pixel, |
||||
const SDL_PixelFormat * format, |
||||
Uint8 * r, Uint8 * g, Uint8 * b, |
||||
Uint8 * a); |
||||
|
||||
/**
|
||||
* \brief Calculate a 256 entry gamma ramp for a gamma value. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_CalculateGammaRamp(float gamma, Uint16 * ramp); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_pixels_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,198 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_platform.h |
||||
* |
||||
* Try to get a standard set of platform defines. |
||||
*/ |
||||
|
||||
#ifndef SDL_platform_h_ |
||||
#define SDL_platform_h_ |
||||
|
||||
#if defined(_AIX) |
||||
#undef __AIX__ |
||||
#define __AIX__ 1 |
||||
#endif |
||||
#if defined(__HAIKU__) |
||||
#undef __HAIKU__ |
||||
#define __HAIKU__ 1 |
||||
#endif |
||||
#if defined(bsdi) || defined(__bsdi) || defined(__bsdi__) |
||||
#undef __BSDI__ |
||||
#define __BSDI__ 1 |
||||
#endif |
||||
#if defined(_arch_dreamcast) |
||||
#undef __DREAMCAST__ |
||||
#define __DREAMCAST__ 1 |
||||
#endif |
||||
#if defined(__FreeBSD__) || defined(__FreeBSD_kernel__) || defined(__DragonFly__) |
||||
#undef __FREEBSD__ |
||||
#define __FREEBSD__ 1 |
||||
#endif |
||||
#if defined(hpux) || defined(__hpux) || defined(__hpux__) |
||||
#undef __HPUX__ |
||||
#define __HPUX__ 1 |
||||
#endif |
||||
#if defined(sgi) || defined(__sgi) || defined(__sgi__) || defined(_SGI_SOURCE) |
||||
#undef __IRIX__ |
||||
#define __IRIX__ 1 |
||||
#endif |
||||
#if (defined(linux) || defined(__linux) || defined(__linux__)) |
||||
#undef __LINUX__ |
||||
#define __LINUX__ 1 |
||||
#endif |
||||
#if defined(ANDROID) || defined(__ANDROID__) |
||||
#undef __ANDROID__ |
||||
#undef __LINUX__ /* do we need to do this? */ |
||||
#define __ANDROID__ 1 |
||||
#endif |
||||
|
||||
#if defined(__APPLE__) |
||||
/* lets us know what version of Mac OS X we're compiling on */ |
||||
#include "AvailabilityMacros.h" |
||||
#include "TargetConditionals.h" |
||||
#if TARGET_OS_TV |
||||
#undef __TVOS__ |
||||
#define __TVOS__ 1 |
||||
#endif |
||||
#if TARGET_OS_IPHONE |
||||
/* if compiling for iOS */ |
||||
#undef __IPHONEOS__ |
||||
#define __IPHONEOS__ 1 |
||||
#undef __MACOSX__ |
||||
#else |
||||
/* if not compiling for iOS */ |
||||
#undef __MACOSX__ |
||||
#define __MACOSX__ 1 |
||||
#if MAC_OS_X_VERSION_MIN_REQUIRED < 1060 |
||||
# error SDL for Mac OS X only supports deploying on 10.6 and above. |
||||
#endif /* MAC_OS_X_VERSION_MIN_REQUIRED < 1060 */ |
||||
#endif /* TARGET_OS_IPHONE */ |
||||
#endif /* defined(__APPLE__) */ |
||||
|
||||
#if defined(__NetBSD__) |
||||
#undef __NETBSD__ |
||||
#define __NETBSD__ 1 |
||||
#endif |
||||
#if defined(__OpenBSD__) |
||||
#undef __OPENBSD__ |
||||
#define __OPENBSD__ 1 |
||||
#endif |
||||
#if defined(__OS2__) || defined(__EMX__) |
||||
#undef __OS2__ |
||||
#define __OS2__ 1 |
||||
#endif |
||||
#if defined(osf) || defined(__osf) || defined(__osf__) || defined(_OSF_SOURCE) |
||||
#undef __OSF__ |
||||
#define __OSF__ 1 |
||||
#endif |
||||
#if defined(__QNXNTO__) |
||||
#undef __QNXNTO__ |
||||
#define __QNXNTO__ 1 |
||||
#endif |
||||
#if defined(riscos) || defined(__riscos) || defined(__riscos__) |
||||
#undef __RISCOS__ |
||||
#define __RISCOS__ 1 |
||||
#endif |
||||
#if defined(__sun) && defined(__SVR4) |
||||
#undef __SOLARIS__ |
||||
#define __SOLARIS__ 1 |
||||
#endif |
||||
|
||||
#if defined(WIN32) || defined(_WIN32) || defined(__CYGWIN__) || defined(__MINGW32__) |
||||
/* Try to find out if we're compiling for WinRT or non-WinRT */ |
||||
#if defined(_MSC_VER) && defined(__has_include) |
||||
#if __has_include(<winapifamily.h>) |
||||
#define HAVE_WINAPIFAMILY_H 1 |
||||
#else |
||||
#define HAVE_WINAPIFAMILY_H 0 |
||||
#endif |
||||
|
||||
/* If _USING_V110_SDK71_ is defined it means we are using the Windows XP toolset. */ |
||||
#elif defined(_MSC_VER) && (_MSC_VER >= 1700 && !_USING_V110_SDK71_) /* _MSC_VER == 1700 for Visual Studio 2012 */ |
||||
#define HAVE_WINAPIFAMILY_H 1 |
||||
#else |
||||
#define HAVE_WINAPIFAMILY_H 0 |
||||
#endif |
||||
|
||||
#if HAVE_WINAPIFAMILY_H |
||||
#include <winapifamily.h> |
||||
#define WINAPI_FAMILY_WINRT (!WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_DESKTOP) && WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_APP)) |
||||
#else |
||||
#define WINAPI_FAMILY_WINRT 0 |
||||
#endif /* HAVE_WINAPIFAMILY_H */ |
||||
|
||||
#if WINAPI_FAMILY_WINRT |
||||
#undef __WINRT__ |
||||
#define __WINRT__ 1 |
||||
#else |
||||
#undef __WINDOWS__ |
||||
#define __WINDOWS__ 1 |
||||
#endif |
||||
#endif /* defined(WIN32) || defined(_WIN32) || defined(__CYGWIN__) */ |
||||
|
||||
#if defined(__WINDOWS__) |
||||
#undef __WIN32__ |
||||
#define __WIN32__ 1 |
||||
#endif |
||||
#if defined(__PSP__) |
||||
#undef __PSP__ |
||||
#define __PSP__ 1 |
||||
#endif |
||||
|
||||
/* The NACL compiler defines __native_client__ and __pnacl__
|
||||
* Ref: http://www.chromium.org/nativeclient/pnacl/stability-of-the-pnacl-bitcode-abi
|
||||
*/ |
||||
#if defined(__native_client__) |
||||
#undef __LINUX__ |
||||
#undef __NACL__ |
||||
#define __NACL__ 1 |
||||
#endif |
||||
#if defined(__pnacl__) |
||||
#undef __LINUX__ |
||||
#undef __PNACL__ |
||||
#define __PNACL__ 1 |
||||
/* PNACL with newlib supports static linking only */ |
||||
#define __SDL_NOGETPROCADDR__ |
||||
#endif |
||||
|
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief Gets the name of the platform. |
||||
*/ |
||||
extern DECLSPEC const char * SDLCALL SDL_GetPlatform (void); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_platform_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,75 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
#ifndef SDL_power_h_ |
||||
#define SDL_power_h_ |
||||
|
||||
/**
|
||||
* \file SDL_power.h |
||||
* |
||||
* Header for the SDL power management routines. |
||||
*/ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief The basic state for the system's power supply. |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_POWERSTATE_UNKNOWN, /**< cannot determine power status */ |
||||
SDL_POWERSTATE_ON_BATTERY, /**< Not plugged in, running on the battery */ |
||||
SDL_POWERSTATE_NO_BATTERY, /**< Plugged in, no battery available */ |
||||
SDL_POWERSTATE_CHARGING, /**< Plugged in, charging battery */ |
||||
SDL_POWERSTATE_CHARGED /**< Plugged in, battery charged */ |
||||
} SDL_PowerState; |
||||
|
||||
|
||||
/**
|
||||
* \brief Get the current power supply details. |
||||
* |
||||
* \param secs Seconds of battery life left. You can pass a NULL here if |
||||
* you don't care. Will return -1 if we can't determine a |
||||
* value, or we're not running on a battery. |
||||
* |
||||
* \param pct Percentage of battery life left, between 0 and 100. You can |
||||
* pass a NULL here if you don't care. Will return -1 if we |
||||
* can't determine a value, or we're not running on a battery. |
||||
* |
||||
* \return The state of the battery (if any). |
||||
*/ |
||||
extern DECLSPEC SDL_PowerState SDLCALL SDL_GetPowerInfo(int *secs, int *pct); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_power_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,58 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_quit.h |
||||
* |
||||
* Include file for SDL quit event handling. |
||||
*/ |
||||
|
||||
#ifndef SDL_quit_h_ |
||||
#define SDL_quit_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
|
||||
/**
|
||||
* \file SDL_quit.h |
||||
* |
||||
* An ::SDL_QUIT event is generated when the user tries to close the application |
||||
* window. If it is ignored or filtered out, the window will remain open. |
||||
* If it is not ignored or filtered, it is queued normally and the window |
||||
* is allowed to close. When the window is closed, screen updates will |
||||
* complete, but have no effect. |
||||
* |
||||
* SDL_Init() installs signal handlers for SIGINT (keyboard interrupt) |
||||
* and SIGTERM (system termination request), if handlers do not already |
||||
* exist, that generate ::SDL_QUIT events as well. There is no way |
||||
* to determine the cause of an ::SDL_QUIT event, but setting a signal |
||||
* handler in your application will override the default generation of |
||||
* quit events for that signal. |
||||
* |
||||
* \sa SDL_Quit() |
||||
*/ |
||||
|
||||
/* There are no functions directly affecting the quit event */ |
||||
|
||||
#define SDL_QuitRequested() \ |
||||
(SDL_PumpEvents(), (SDL_PeepEvents(NULL,0,SDL_PEEKEVENT,SDL_QUIT,SDL_QUIT) > 0)) |
||||
|
||||
#endif /* SDL_quit_h_ */ |
||||
@ -0,0 +1,174 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_rect.h |
||||
* |
||||
* Header file for SDL_rect definition and management functions. |
||||
*/ |
||||
|
||||
#ifndef SDL_rect_h_ |
||||
#define SDL_rect_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
#include "SDL_pixels.h" |
||||
#include "SDL_rwops.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief The structure that defines a point (integer) |
||||
* |
||||
* \sa SDL_EnclosePoints |
||||
* \sa SDL_PointInRect |
||||
*/ |
||||
typedef struct SDL_Point |
||||
{ |
||||
int x; |
||||
int y; |
||||
} SDL_Point; |
||||
|
||||
/**
|
||||
* \brief The structure that defines a point (floating point) |
||||
* |
||||
* \sa SDL_EnclosePoints |
||||
* \sa SDL_PointInRect |
||||
*/ |
||||
typedef struct SDL_FPoint |
||||
{ |
||||
float x; |
||||
float y; |
||||
} SDL_FPoint; |
||||
|
||||
|
||||
/**
|
||||
* \brief A rectangle, with the origin at the upper left (integer). |
||||
* |
||||
* \sa SDL_RectEmpty |
||||
* \sa SDL_RectEquals |
||||
* \sa SDL_HasIntersection |
||||
* \sa SDL_IntersectRect |
||||
* \sa SDL_UnionRect |
||||
* \sa SDL_EnclosePoints |
||||
*/ |
||||
typedef struct SDL_Rect |
||||
{ |
||||
int x, y; |
||||
int w, h; |
||||
} SDL_Rect; |
||||
|
||||
|
||||
/**
|
||||
* \brief A rectangle, with the origin at the upper left (floating point). |
||||
*/ |
||||
typedef struct SDL_FRect |
||||
{ |
||||
float x; |
||||
float y; |
||||
float w; |
||||
float h; |
||||
} SDL_FRect; |
||||
|
||||
|
||||
/**
|
||||
* \brief Returns true if point resides inside a rectangle. |
||||
*/ |
||||
SDL_FORCE_INLINE SDL_bool SDL_PointInRect(const SDL_Point *p, const SDL_Rect *r) |
||||
{ |
||||
return ( (p->x >= r->x) && (p->x < (r->x + r->w)) && |
||||
(p->y >= r->y) && (p->y < (r->y + r->h)) ) ? SDL_TRUE : SDL_FALSE; |
||||
} |
||||
|
||||
/**
|
||||
* \brief Returns true if the rectangle has no area. |
||||
*/ |
||||
SDL_FORCE_INLINE SDL_bool SDL_RectEmpty(const SDL_Rect *r) |
||||
{ |
||||
return ((!r) || (r->w <= 0) || (r->h <= 0)) ? SDL_TRUE : SDL_FALSE; |
||||
} |
||||
|
||||
/**
|
||||
* \brief Returns true if the two rectangles are equal. |
||||
*/ |
||||
SDL_FORCE_INLINE SDL_bool SDL_RectEquals(const SDL_Rect *a, const SDL_Rect *b) |
||||
{ |
||||
return (a && b && (a->x == b->x) && (a->y == b->y) && |
||||
(a->w == b->w) && (a->h == b->h)) ? SDL_TRUE : SDL_FALSE; |
||||
} |
||||
|
||||
/**
|
||||
* \brief Determine whether two rectangles intersect. |
||||
* |
||||
* \return SDL_TRUE if there is an intersection, SDL_FALSE otherwise. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasIntersection(const SDL_Rect * A, |
||||
const SDL_Rect * B); |
||||
|
||||
/**
|
||||
* \brief Calculate the intersection of two rectangles. |
||||
* |
||||
* \return SDL_TRUE if there is an intersection, SDL_FALSE otherwise. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_IntersectRect(const SDL_Rect * A, |
||||
const SDL_Rect * B, |
||||
SDL_Rect * result); |
||||
|
||||
/**
|
||||
* \brief Calculate the union of two rectangles. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_UnionRect(const SDL_Rect * A, |
||||
const SDL_Rect * B, |
||||
SDL_Rect * result); |
||||
|
||||
/**
|
||||
* \brief Calculate a minimal rectangle enclosing a set of points |
||||
* |
||||
* \return SDL_TRUE if any points were within the clipping rect |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_EnclosePoints(const SDL_Point * points, |
||||
int count, |
||||
const SDL_Rect * clip, |
||||
SDL_Rect * result); |
||||
|
||||
/**
|
||||
* \brief Calculate the intersection of a rectangle and line segment. |
||||
* |
||||
* \return SDL_TRUE if there is an intersection, SDL_FALSE otherwise. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_IntersectRectAndLine(const SDL_Rect * |
||||
rect, int *X1, |
||||
int *Y1, int *X2, |
||||
int *Y2); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_rect_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,2 @@ |
||||
#define SDL_REVISION "hg-12952:bc90ce38f1e2" |
||||
#define SDL_REVISION_NUMBER 12952 |
||||
@ -0,0 +1,291 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_rwops.h |
||||
* |
||||
* This file provides a general interface for SDL to read and write |
||||
* data streams. It can easily be extended to files, memory, etc. |
||||
*/ |
||||
|
||||
#ifndef SDL_rwops_h_ |
||||
#define SDL_rwops_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* RWops Types */ |
||||
#define SDL_RWOPS_UNKNOWN 0U /**< Unknown stream type */ |
||||
#define SDL_RWOPS_WINFILE 1U /**< Win32 file */ |
||||
#define SDL_RWOPS_STDFILE 2U /**< Stdio file */ |
||||
#define SDL_RWOPS_JNIFILE 3U /**< Android asset */ |
||||
#define SDL_RWOPS_MEMORY 4U /**< Memory stream */ |
||||
#define SDL_RWOPS_MEMORY_RO 5U /**< Read-Only memory stream */ |
||||
|
||||
/**
|
||||
* This is the read/write operation structure -- very basic. |
||||
*/ |
||||
typedef struct SDL_RWops |
||||
{ |
||||
/**
|
||||
* Return the size of the file in this rwops, or -1 if unknown |
||||
*/ |
||||
Sint64 (SDLCALL * size) (struct SDL_RWops * context); |
||||
|
||||
/**
|
||||
* Seek to \c offset relative to \c whence, one of stdio's whence values: |
||||
* RW_SEEK_SET, RW_SEEK_CUR, RW_SEEK_END |
||||
* |
||||
* \return the final offset in the data stream, or -1 on error. |
||||
*/ |
||||
Sint64 (SDLCALL * seek) (struct SDL_RWops * context, Sint64 offset, |
||||
int whence); |
||||
|
||||
/**
|
||||
* Read up to \c maxnum objects each of size \c size from the data |
||||
* stream to the area pointed at by \c ptr. |
||||
* |
||||
* \return the number of objects read, or 0 at error or end of file. |
||||
*/ |
||||
size_t (SDLCALL * read) (struct SDL_RWops * context, void *ptr, |
||||
size_t size, size_t maxnum); |
||||
|
||||
/**
|
||||
* Write exactly \c num objects each of size \c size from the area |
||||
* pointed at by \c ptr to data stream. |
||||
* |
||||
* \return the number of objects written, or 0 at error or end of file. |
||||
*/ |
||||
size_t (SDLCALL * write) (struct SDL_RWops * context, const void *ptr, |
||||
size_t size, size_t num); |
||||
|
||||
/**
|
||||
* Close and free an allocated SDL_RWops structure. |
||||
* |
||||
* \return 0 if successful or -1 on write error when flushing data. |
||||
*/ |
||||
int (SDLCALL * close) (struct SDL_RWops * context); |
||||
|
||||
Uint32 type; |
||||
union |
||||
{ |
||||
#if defined(__ANDROID__) |
||||
struct |
||||
{ |
||||
void *fileNameRef; |
||||
void *inputStreamRef; |
||||
void *readableByteChannelRef; |
||||
void *readMethod; |
||||
void *assetFileDescriptorRef; |
||||
long position; |
||||
long size; |
||||
long offset; |
||||
int fd; |
||||
} androidio; |
||||
#elif defined(__WIN32__) |
||||
struct |
||||
{ |
||||
SDL_bool append; |
||||
void *h; |
||||
struct |
||||
{ |
||||
void *data; |
||||
size_t size; |
||||
size_t left; |
||||
} buffer; |
||||
} windowsio; |
||||
#endif |
||||
|
||||
#ifdef HAVE_STDIO_H |
||||
struct |
||||
{ |
||||
SDL_bool autoclose; |
||||
FILE *fp; |
||||
} stdio; |
||||
#endif |
||||
struct |
||||
{ |
||||
Uint8 *base; |
||||
Uint8 *here; |
||||
Uint8 *stop; |
||||
} mem; |
||||
struct |
||||
{ |
||||
void *data1; |
||||
void *data2; |
||||
} unknown; |
||||
} hidden; |
||||
|
||||
} SDL_RWops; |
||||
|
||||
|
||||
/**
|
||||
* \name RWFrom functions |
||||
* |
||||
* Functions to create SDL_RWops structures from various data streams. |
||||
*/ |
||||
/* @{ */ |
||||
|
||||
extern DECLSPEC SDL_RWops *SDLCALL SDL_RWFromFile(const char *file, |
||||
const char *mode); |
||||
|
||||
#ifdef HAVE_STDIO_H |
||||
extern DECLSPEC SDL_RWops *SDLCALL SDL_RWFromFP(FILE * fp, |
||||
SDL_bool autoclose); |
||||
#else |
||||
extern DECLSPEC SDL_RWops *SDLCALL SDL_RWFromFP(void * fp, |
||||
SDL_bool autoclose); |
||||
#endif |
||||
|
||||
extern DECLSPEC SDL_RWops *SDLCALL SDL_RWFromMem(void *mem, int size); |
||||
extern DECLSPEC SDL_RWops *SDLCALL SDL_RWFromConstMem(const void *mem, |
||||
int size); |
||||
|
||||
/* @} *//* RWFrom functions */ |
||||
|
||||
|
||||
extern DECLSPEC SDL_RWops *SDLCALL SDL_AllocRW(void); |
||||
extern DECLSPEC void SDLCALL SDL_FreeRW(SDL_RWops * area); |
||||
|
||||
#define RW_SEEK_SET 0 /**< Seek from the beginning of data */ |
||||
#define RW_SEEK_CUR 1 /**< Seek relative to current read point */ |
||||
#define RW_SEEK_END 2 /**< Seek relative to the end of data */ |
||||
|
||||
/**
|
||||
* Return the size of the file in this rwops, or -1 if unknown |
||||
*/ |
||||
extern DECLSPEC Sint64 SDLCALL SDL_RWsize(SDL_RWops *context); |
||||
|
||||
/**
|
||||
* Seek to \c offset relative to \c whence, one of stdio's whence values: |
||||
* RW_SEEK_SET, RW_SEEK_CUR, RW_SEEK_END |
||||
* |
||||
* \return the final offset in the data stream, or -1 on error. |
||||
*/ |
||||
extern DECLSPEC Sint64 SDLCALL SDL_RWseek(SDL_RWops *context, |
||||
Sint64 offset, int whence); |
||||
|
||||
/**
|
||||
* Return the current offset in the data stream, or -1 on error. |
||||
*/ |
||||
extern DECLSPEC Sint64 SDLCALL SDL_RWtell(SDL_RWops *context); |
||||
|
||||
/**
|
||||
* Read up to \c maxnum objects each of size \c size from the data |
||||
* stream to the area pointed at by \c ptr. |
||||
* |
||||
* \return the number of objects read, or 0 at error or end of file. |
||||
*/ |
||||
extern DECLSPEC size_t SDLCALL SDL_RWread(SDL_RWops *context, |
||||
void *ptr, size_t size, size_t maxnum); |
||||
|
||||
/**
|
||||
* Write exactly \c num objects each of size \c size from the area |
||||
* pointed at by \c ptr to data stream. |
||||
* |
||||
* \return the number of objects written, or 0 at error or end of file. |
||||
*/ |
||||
extern DECLSPEC size_t SDLCALL SDL_RWwrite(SDL_RWops *context, |
||||
const void *ptr, size_t size, size_t num); |
||||
|
||||
/**
|
||||
* Close and free an allocated SDL_RWops structure. |
||||
* |
||||
* \return 0 if successful or -1 on write error when flushing data. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_RWclose(SDL_RWops *context); |
||||
|
||||
/**
|
||||
* Load all the data from an SDL data stream. |
||||
* |
||||
* The data is allocated with a zero byte at the end (null terminated) |
||||
* |
||||
* If \c datasize is not NULL, it is filled with the size of the data read. |
||||
* |
||||
* If \c freesrc is non-zero, the stream will be closed after being read. |
||||
* |
||||
* The data should be freed with SDL_free(). |
||||
* |
||||
* \return the data, or NULL if there was an error. |
||||
*/ |
||||
extern DECLSPEC void *SDLCALL SDL_LoadFile_RW(SDL_RWops * src, size_t *datasize, |
||||
int freesrc); |
||||
|
||||
/**
|
||||
* Load an entire file. |
||||
* |
||||
* The data is allocated with a zero byte at the end (null terminated) |
||||
* |
||||
* If \c datasize is not NULL, it is filled with the size of the data read. |
||||
* |
||||
* If \c freesrc is non-zero, the stream will be closed after being read. |
||||
* |
||||
* The data should be freed with SDL_free(). |
||||
* |
||||
* \return the data, or NULL if there was an error. |
||||
*/ |
||||
extern DECLSPEC void *SDLCALL SDL_LoadFile(const char *file, size_t *datasize); |
||||
|
||||
/**
|
||||
* \name Read endian functions |
||||
* |
||||
* Read an item of the specified endianness and return in native format. |
||||
*/ |
||||
/* @{ */ |
||||
extern DECLSPEC Uint8 SDLCALL SDL_ReadU8(SDL_RWops * src); |
||||
extern DECLSPEC Uint16 SDLCALL SDL_ReadLE16(SDL_RWops * src); |
||||
extern DECLSPEC Uint16 SDLCALL SDL_ReadBE16(SDL_RWops * src); |
||||
extern DECLSPEC Uint32 SDLCALL SDL_ReadLE32(SDL_RWops * src); |
||||
extern DECLSPEC Uint32 SDLCALL SDL_ReadBE32(SDL_RWops * src); |
||||
extern DECLSPEC Uint64 SDLCALL SDL_ReadLE64(SDL_RWops * src); |
||||
extern DECLSPEC Uint64 SDLCALL SDL_ReadBE64(SDL_RWops * src); |
||||
/* @} *//* Read endian functions */ |
||||
|
||||
/**
|
||||
* \name Write endian functions |
||||
* |
||||
* Write an item of native format to the specified endianness. |
||||
*/ |
||||
/* @{ */ |
||||
extern DECLSPEC size_t SDLCALL SDL_WriteU8(SDL_RWops * dst, Uint8 value); |
||||
extern DECLSPEC size_t SDLCALL SDL_WriteLE16(SDL_RWops * dst, Uint16 value); |
||||
extern DECLSPEC size_t SDLCALL SDL_WriteBE16(SDL_RWops * dst, Uint16 value); |
||||
extern DECLSPEC size_t SDLCALL SDL_WriteLE32(SDL_RWops * dst, Uint32 value); |
||||
extern DECLSPEC size_t SDLCALL SDL_WriteBE32(SDL_RWops * dst, Uint32 value); |
||||
extern DECLSPEC size_t SDLCALL SDL_WriteLE64(SDL_RWops * dst, Uint64 value); |
||||
extern DECLSPEC size_t SDLCALL SDL_WriteBE64(SDL_RWops * dst, Uint64 value); |
||||
/* @} *//* Write endian functions */ |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_rwops_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,413 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_scancode.h |
||||
* |
||||
* Defines keyboard scancodes. |
||||
*/ |
||||
|
||||
#ifndef SDL_scancode_h_ |
||||
#define SDL_scancode_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
|
||||
/**
|
||||
* \brief The SDL keyboard scancode representation. |
||||
* |
||||
* Values of this type are used to represent keyboard keys, among other places |
||||
* in the \link SDL_Keysym::scancode key.keysym.scancode \endlink field of the |
||||
* SDL_Event structure. |
||||
* |
||||
* The values in this enumeration are based on the USB usage page standard: |
||||
* https://www.usb.org/sites/default/files/documents/hut1_12v2.pdf
|
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_SCANCODE_UNKNOWN = 0, |
||||
|
||||
/**
|
||||
* \name Usage page 0x07 |
||||
* |
||||
* These values are from usage page 0x07 (USB keyboard page). |
||||
*/ |
||||
/* @{ */ |
||||
|
||||
SDL_SCANCODE_A = 4, |
||||
SDL_SCANCODE_B = 5, |
||||
SDL_SCANCODE_C = 6, |
||||
SDL_SCANCODE_D = 7, |
||||
SDL_SCANCODE_E = 8, |
||||
SDL_SCANCODE_F = 9, |
||||
SDL_SCANCODE_G = 10, |
||||
SDL_SCANCODE_H = 11, |
||||
SDL_SCANCODE_I = 12, |
||||
SDL_SCANCODE_J = 13, |
||||
SDL_SCANCODE_K = 14, |
||||
SDL_SCANCODE_L = 15, |
||||
SDL_SCANCODE_M = 16, |
||||
SDL_SCANCODE_N = 17, |
||||
SDL_SCANCODE_O = 18, |
||||
SDL_SCANCODE_P = 19, |
||||
SDL_SCANCODE_Q = 20, |
||||
SDL_SCANCODE_R = 21, |
||||
SDL_SCANCODE_S = 22, |
||||
SDL_SCANCODE_T = 23, |
||||
SDL_SCANCODE_U = 24, |
||||
SDL_SCANCODE_V = 25, |
||||
SDL_SCANCODE_W = 26, |
||||
SDL_SCANCODE_X = 27, |
||||
SDL_SCANCODE_Y = 28, |
||||
SDL_SCANCODE_Z = 29, |
||||
|
||||
SDL_SCANCODE_1 = 30, |
||||
SDL_SCANCODE_2 = 31, |
||||
SDL_SCANCODE_3 = 32, |
||||
SDL_SCANCODE_4 = 33, |
||||
SDL_SCANCODE_5 = 34, |
||||
SDL_SCANCODE_6 = 35, |
||||
SDL_SCANCODE_7 = 36, |
||||
SDL_SCANCODE_8 = 37, |
||||
SDL_SCANCODE_9 = 38, |
||||
SDL_SCANCODE_0 = 39, |
||||
|
||||
SDL_SCANCODE_RETURN = 40, |
||||
SDL_SCANCODE_ESCAPE = 41, |
||||
SDL_SCANCODE_BACKSPACE = 42, |
||||
SDL_SCANCODE_TAB = 43, |
||||
SDL_SCANCODE_SPACE = 44, |
||||
|
||||
SDL_SCANCODE_MINUS = 45, |
||||
SDL_SCANCODE_EQUALS = 46, |
||||
SDL_SCANCODE_LEFTBRACKET = 47, |
||||
SDL_SCANCODE_RIGHTBRACKET = 48, |
||||
SDL_SCANCODE_BACKSLASH = 49, /**< Located at the lower left of the return
|
||||
* key on ISO keyboards and at the right end |
||||
* of the QWERTY row on ANSI keyboards. |
||||
* Produces REVERSE SOLIDUS (backslash) and |
||||
* VERTICAL LINE in a US layout, REVERSE |
||||
* SOLIDUS and VERTICAL LINE in a UK Mac |
||||
* layout, NUMBER SIGN and TILDE in a UK |
||||
* Windows layout, DOLLAR SIGN and POUND SIGN |
||||
* in a Swiss German layout, NUMBER SIGN and |
||||
* APOSTROPHE in a German layout, GRAVE |
||||
* ACCENT and POUND SIGN in a French Mac |
||||
* layout, and ASTERISK and MICRO SIGN in a |
||||
* French Windows layout. |
||||
*/ |
||||
SDL_SCANCODE_NONUSHASH = 50, /**< ISO USB keyboards actually use this code
|
||||
* instead of 49 for the same key, but all |
||||
* OSes I've seen treat the two codes |
||||
* identically. So, as an implementor, unless |
||||
* your keyboard generates both of those |
||||
* codes and your OS treats them differently, |
||||
* you should generate SDL_SCANCODE_BACKSLASH |
||||
* instead of this code. As a user, you |
||||
* should not rely on this code because SDL |
||||
* will never generate it with most (all?) |
||||
* keyboards. |
||||
*/ |
||||
SDL_SCANCODE_SEMICOLON = 51, |
||||
SDL_SCANCODE_APOSTROPHE = 52, |
||||
SDL_SCANCODE_GRAVE = 53, /**< Located in the top left corner (on both ANSI
|
||||
* and ISO keyboards). Produces GRAVE ACCENT and |
||||
* TILDE in a US Windows layout and in US and UK |
||||
* Mac layouts on ANSI keyboards, GRAVE ACCENT |
||||
* and NOT SIGN in a UK Windows layout, SECTION |
||||
* SIGN and PLUS-MINUS SIGN in US and UK Mac |
||||
* layouts on ISO keyboards, SECTION SIGN and |
||||
* DEGREE SIGN in a Swiss German layout (Mac: |
||||
* only on ISO keyboards), CIRCUMFLEX ACCENT and |
||||
* DEGREE SIGN in a German layout (Mac: only on |
||||
* ISO keyboards), SUPERSCRIPT TWO and TILDE in a |
||||
* French Windows layout, COMMERCIAL AT and |
||||
* NUMBER SIGN in a French Mac layout on ISO |
||||
* keyboards, and LESS-THAN SIGN and GREATER-THAN |
||||
* SIGN in a Swiss German, German, or French Mac |
||||
* layout on ANSI keyboards. |
||||
*/ |
||||
SDL_SCANCODE_COMMA = 54, |
||||
SDL_SCANCODE_PERIOD = 55, |
||||
SDL_SCANCODE_SLASH = 56, |
||||
|
||||
SDL_SCANCODE_CAPSLOCK = 57, |
||||
|
||||
SDL_SCANCODE_F1 = 58, |
||||
SDL_SCANCODE_F2 = 59, |
||||
SDL_SCANCODE_F3 = 60, |
||||
SDL_SCANCODE_F4 = 61, |
||||
SDL_SCANCODE_F5 = 62, |
||||
SDL_SCANCODE_F6 = 63, |
||||
SDL_SCANCODE_F7 = 64, |
||||
SDL_SCANCODE_F8 = 65, |
||||
SDL_SCANCODE_F9 = 66, |
||||
SDL_SCANCODE_F10 = 67, |
||||
SDL_SCANCODE_F11 = 68, |
||||
SDL_SCANCODE_F12 = 69, |
||||
|
||||
SDL_SCANCODE_PRINTSCREEN = 70, |
||||
SDL_SCANCODE_SCROLLLOCK = 71, |
||||
SDL_SCANCODE_PAUSE = 72, |
||||
SDL_SCANCODE_INSERT = 73, /**< insert on PC, help on some Mac keyboards (but
|
||||
does send code 73, not 117) */ |
||||
SDL_SCANCODE_HOME = 74, |
||||
SDL_SCANCODE_PAGEUP = 75, |
||||
SDL_SCANCODE_DELETE = 76, |
||||
SDL_SCANCODE_END = 77, |
||||
SDL_SCANCODE_PAGEDOWN = 78, |
||||
SDL_SCANCODE_RIGHT = 79, |
||||
SDL_SCANCODE_LEFT = 80, |
||||
SDL_SCANCODE_DOWN = 81, |
||||
SDL_SCANCODE_UP = 82, |
||||
|
||||
SDL_SCANCODE_NUMLOCKCLEAR = 83, /**< num lock on PC, clear on Mac keyboards
|
||||
*/ |
||||
SDL_SCANCODE_KP_DIVIDE = 84, |
||||
SDL_SCANCODE_KP_MULTIPLY = 85, |
||||
SDL_SCANCODE_KP_MINUS = 86, |
||||
SDL_SCANCODE_KP_PLUS = 87, |
||||
SDL_SCANCODE_KP_ENTER = 88, |
||||
SDL_SCANCODE_KP_1 = 89, |
||||
SDL_SCANCODE_KP_2 = 90, |
||||
SDL_SCANCODE_KP_3 = 91, |
||||
SDL_SCANCODE_KP_4 = 92, |
||||
SDL_SCANCODE_KP_5 = 93, |
||||
SDL_SCANCODE_KP_6 = 94, |
||||
SDL_SCANCODE_KP_7 = 95, |
||||
SDL_SCANCODE_KP_8 = 96, |
||||
SDL_SCANCODE_KP_9 = 97, |
||||
SDL_SCANCODE_KP_0 = 98, |
||||
SDL_SCANCODE_KP_PERIOD = 99, |
||||
|
||||
SDL_SCANCODE_NONUSBACKSLASH = 100, /**< This is the additional key that ISO
|
||||
* keyboards have over ANSI ones, |
||||
* located between left shift and Y. |
||||
* Produces GRAVE ACCENT and TILDE in a |
||||
* US or UK Mac layout, REVERSE SOLIDUS |
||||
* (backslash) and VERTICAL LINE in a |
||||
* US or UK Windows layout, and |
||||
* LESS-THAN SIGN and GREATER-THAN SIGN |
||||
* in a Swiss German, German, or French |
||||
* layout. */ |
||||
SDL_SCANCODE_APPLICATION = 101, /**< windows contextual menu, compose */ |
||||
SDL_SCANCODE_POWER = 102, /**< The USB document says this is a status flag,
|
||||
* not a physical key - but some Mac keyboards |
||||
* do have a power key. */ |
||||
SDL_SCANCODE_KP_EQUALS = 103, |
||||
SDL_SCANCODE_F13 = 104, |
||||
SDL_SCANCODE_F14 = 105, |
||||
SDL_SCANCODE_F15 = 106, |
||||
SDL_SCANCODE_F16 = 107, |
||||
SDL_SCANCODE_F17 = 108, |
||||
SDL_SCANCODE_F18 = 109, |
||||
SDL_SCANCODE_F19 = 110, |
||||
SDL_SCANCODE_F20 = 111, |
||||
SDL_SCANCODE_F21 = 112, |
||||
SDL_SCANCODE_F22 = 113, |
||||
SDL_SCANCODE_F23 = 114, |
||||
SDL_SCANCODE_F24 = 115, |
||||
SDL_SCANCODE_EXECUTE = 116, |
||||
SDL_SCANCODE_HELP = 117, |
||||
SDL_SCANCODE_MENU = 118, |
||||
SDL_SCANCODE_SELECT = 119, |
||||
SDL_SCANCODE_STOP = 120, |
||||
SDL_SCANCODE_AGAIN = 121, /**< redo */ |
||||
SDL_SCANCODE_UNDO = 122, |
||||
SDL_SCANCODE_CUT = 123, |
||||
SDL_SCANCODE_COPY = 124, |
||||
SDL_SCANCODE_PASTE = 125, |
||||
SDL_SCANCODE_FIND = 126, |
||||
SDL_SCANCODE_MUTE = 127, |
||||
SDL_SCANCODE_VOLUMEUP = 128, |
||||
SDL_SCANCODE_VOLUMEDOWN = 129, |
||||
/* not sure whether there's a reason to enable these */ |
||||
/* SDL_SCANCODE_LOCKINGCAPSLOCK = 130, */ |
||||
/* SDL_SCANCODE_LOCKINGNUMLOCK = 131, */ |
||||
/* SDL_SCANCODE_LOCKINGSCROLLLOCK = 132, */ |
||||
SDL_SCANCODE_KP_COMMA = 133, |
||||
SDL_SCANCODE_KP_EQUALSAS400 = 134, |
||||
|
||||
SDL_SCANCODE_INTERNATIONAL1 = 135, /**< used on Asian keyboards, see
|
||||
footnotes in USB doc */ |
||||
SDL_SCANCODE_INTERNATIONAL2 = 136, |
||||
SDL_SCANCODE_INTERNATIONAL3 = 137, /**< Yen */ |
||||
SDL_SCANCODE_INTERNATIONAL4 = 138, |
||||
SDL_SCANCODE_INTERNATIONAL5 = 139, |
||||
SDL_SCANCODE_INTERNATIONAL6 = 140, |
||||
SDL_SCANCODE_INTERNATIONAL7 = 141, |
||||
SDL_SCANCODE_INTERNATIONAL8 = 142, |
||||
SDL_SCANCODE_INTERNATIONAL9 = 143, |
||||
SDL_SCANCODE_LANG1 = 144, /**< Hangul/English toggle */ |
||||
SDL_SCANCODE_LANG2 = 145, /**< Hanja conversion */ |
||||
SDL_SCANCODE_LANG3 = 146, /**< Katakana */ |
||||
SDL_SCANCODE_LANG4 = 147, /**< Hiragana */ |
||||
SDL_SCANCODE_LANG5 = 148, /**< Zenkaku/Hankaku */ |
||||
SDL_SCANCODE_LANG6 = 149, /**< reserved */ |
||||
SDL_SCANCODE_LANG7 = 150, /**< reserved */ |
||||
SDL_SCANCODE_LANG8 = 151, /**< reserved */ |
||||
SDL_SCANCODE_LANG9 = 152, /**< reserved */ |
||||
|
||||
SDL_SCANCODE_ALTERASE = 153, /**< Erase-Eaze */ |
||||
SDL_SCANCODE_SYSREQ = 154, |
||||
SDL_SCANCODE_CANCEL = 155, |
||||
SDL_SCANCODE_CLEAR = 156, |
||||
SDL_SCANCODE_PRIOR = 157, |
||||
SDL_SCANCODE_RETURN2 = 158, |
||||
SDL_SCANCODE_SEPARATOR = 159, |
||||
SDL_SCANCODE_OUT = 160, |
||||
SDL_SCANCODE_OPER = 161, |
||||
SDL_SCANCODE_CLEARAGAIN = 162, |
||||
SDL_SCANCODE_CRSEL = 163, |
||||
SDL_SCANCODE_EXSEL = 164, |
||||
|
||||
SDL_SCANCODE_KP_00 = 176, |
||||
SDL_SCANCODE_KP_000 = 177, |
||||
SDL_SCANCODE_THOUSANDSSEPARATOR = 178, |
||||
SDL_SCANCODE_DECIMALSEPARATOR = 179, |
||||
SDL_SCANCODE_CURRENCYUNIT = 180, |
||||
SDL_SCANCODE_CURRENCYSUBUNIT = 181, |
||||
SDL_SCANCODE_KP_LEFTPAREN = 182, |
||||
SDL_SCANCODE_KP_RIGHTPAREN = 183, |
||||
SDL_SCANCODE_KP_LEFTBRACE = 184, |
||||
SDL_SCANCODE_KP_RIGHTBRACE = 185, |
||||
SDL_SCANCODE_KP_TAB = 186, |
||||
SDL_SCANCODE_KP_BACKSPACE = 187, |
||||
SDL_SCANCODE_KP_A = 188, |
||||
SDL_SCANCODE_KP_B = 189, |
||||
SDL_SCANCODE_KP_C = 190, |
||||
SDL_SCANCODE_KP_D = 191, |
||||
SDL_SCANCODE_KP_E = 192, |
||||
SDL_SCANCODE_KP_F = 193, |
||||
SDL_SCANCODE_KP_XOR = 194, |
||||
SDL_SCANCODE_KP_POWER = 195, |
||||
SDL_SCANCODE_KP_PERCENT = 196, |
||||
SDL_SCANCODE_KP_LESS = 197, |
||||
SDL_SCANCODE_KP_GREATER = 198, |
||||
SDL_SCANCODE_KP_AMPERSAND = 199, |
||||
SDL_SCANCODE_KP_DBLAMPERSAND = 200, |
||||
SDL_SCANCODE_KP_VERTICALBAR = 201, |
||||
SDL_SCANCODE_KP_DBLVERTICALBAR = 202, |
||||
SDL_SCANCODE_KP_COLON = 203, |
||||
SDL_SCANCODE_KP_HASH = 204, |
||||
SDL_SCANCODE_KP_SPACE = 205, |
||||
SDL_SCANCODE_KP_AT = 206, |
||||
SDL_SCANCODE_KP_EXCLAM = 207, |
||||
SDL_SCANCODE_KP_MEMSTORE = 208, |
||||
SDL_SCANCODE_KP_MEMRECALL = 209, |
||||
SDL_SCANCODE_KP_MEMCLEAR = 210, |
||||
SDL_SCANCODE_KP_MEMADD = 211, |
||||
SDL_SCANCODE_KP_MEMSUBTRACT = 212, |
||||
SDL_SCANCODE_KP_MEMMULTIPLY = 213, |
||||
SDL_SCANCODE_KP_MEMDIVIDE = 214, |
||||
SDL_SCANCODE_KP_PLUSMINUS = 215, |
||||
SDL_SCANCODE_KP_CLEAR = 216, |
||||
SDL_SCANCODE_KP_CLEARENTRY = 217, |
||||
SDL_SCANCODE_KP_BINARY = 218, |
||||
SDL_SCANCODE_KP_OCTAL = 219, |
||||
SDL_SCANCODE_KP_DECIMAL = 220, |
||||
SDL_SCANCODE_KP_HEXADECIMAL = 221, |
||||
|
||||
SDL_SCANCODE_LCTRL = 224, |
||||
SDL_SCANCODE_LSHIFT = 225, |
||||
SDL_SCANCODE_LALT = 226, /**< alt, option */ |
||||
SDL_SCANCODE_LGUI = 227, /**< windows, command (apple), meta */ |
||||
SDL_SCANCODE_RCTRL = 228, |
||||
SDL_SCANCODE_RSHIFT = 229, |
||||
SDL_SCANCODE_RALT = 230, /**< alt gr, option */ |
||||
SDL_SCANCODE_RGUI = 231, /**< windows, command (apple), meta */ |
||||
|
||||
SDL_SCANCODE_MODE = 257, /**< I'm not sure if this is really not covered
|
||||
* by any of the above, but since there's a |
||||
* special KMOD_MODE for it I'm adding it here |
||||
*/ |
||||
|
||||
/* @} *//* Usage page 0x07 */ |
||||
|
||||
/**
|
||||
* \name Usage page 0x0C |
||||
* |
||||
* These values are mapped from usage page 0x0C (USB consumer page). |
||||
*/ |
||||
/* @{ */ |
||||
|
||||
SDL_SCANCODE_AUDIONEXT = 258, |
||||
SDL_SCANCODE_AUDIOPREV = 259, |
||||
SDL_SCANCODE_AUDIOSTOP = 260, |
||||
SDL_SCANCODE_AUDIOPLAY = 261, |
||||
SDL_SCANCODE_AUDIOMUTE = 262, |
||||
SDL_SCANCODE_MEDIASELECT = 263, |
||||
SDL_SCANCODE_WWW = 264, |
||||
SDL_SCANCODE_MAIL = 265, |
||||
SDL_SCANCODE_CALCULATOR = 266, |
||||
SDL_SCANCODE_COMPUTER = 267, |
||||
SDL_SCANCODE_AC_SEARCH = 268, |
||||
SDL_SCANCODE_AC_HOME = 269, |
||||
SDL_SCANCODE_AC_BACK = 270, |
||||
SDL_SCANCODE_AC_FORWARD = 271, |
||||
SDL_SCANCODE_AC_STOP = 272, |
||||
SDL_SCANCODE_AC_REFRESH = 273, |
||||
SDL_SCANCODE_AC_BOOKMARKS = 274, |
||||
|
||||
/* @} *//* Usage page 0x0C */ |
||||
|
||||
/**
|
||||
* \name Walther keys |
||||
* |
||||
* These are values that Christian Walther added (for mac keyboard?). |
||||
*/ |
||||
/* @{ */ |
||||
|
||||
SDL_SCANCODE_BRIGHTNESSDOWN = 275, |
||||
SDL_SCANCODE_BRIGHTNESSUP = 276, |
||||
SDL_SCANCODE_DISPLAYSWITCH = 277, /**< display mirroring/dual display
|
||||
switch, video mode switch */ |
||||
SDL_SCANCODE_KBDILLUMTOGGLE = 278, |
||||
SDL_SCANCODE_KBDILLUMDOWN = 279, |
||||
SDL_SCANCODE_KBDILLUMUP = 280, |
||||
SDL_SCANCODE_EJECT = 281, |
||||
SDL_SCANCODE_SLEEP = 282, |
||||
|
||||
SDL_SCANCODE_APP1 = 283, |
||||
SDL_SCANCODE_APP2 = 284, |
||||
|
||||
/* @} *//* Walther keys */ |
||||
|
||||
/**
|
||||
* \name Usage page 0x0C (additional media keys) |
||||
* |
||||
* These values are mapped from usage page 0x0C (USB consumer page). |
||||
*/ |
||||
/* @{ */ |
||||
|
||||
SDL_SCANCODE_AUDIOREWIND = 285, |
||||
SDL_SCANCODE_AUDIOFASTFORWARD = 286, |
||||
|
||||
/* @} *//* Usage page 0x0C (additional media keys) */ |
||||
|
||||
/* Add any other keys here. */ |
||||
|
||||
SDL_NUM_SCANCODES = 512 /**< not a key, just marks the number of scancodes
|
||||
for array bounds */ |
||||
} SDL_Scancode; |
||||
|
||||
#endif /* SDL_scancode_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,251 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_sensor.h |
||||
* |
||||
* Include file for SDL sensor event handling |
||||
* |
||||
*/ |
||||
|
||||
#ifndef SDL_sensor_h_ |
||||
#define SDL_sensor_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
/* *INDENT-OFF* */ |
||||
extern "C" { |
||||
/* *INDENT-ON* */ |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief SDL_sensor.h |
||||
* |
||||
* In order to use these functions, SDL_Init() must have been called |
||||
* with the ::SDL_INIT_SENSOR flag. This causes SDL to scan the system |
||||
* for sensors, and load appropriate drivers. |
||||
*/ |
||||
|
||||
struct _SDL_Sensor; |
||||
typedef struct _SDL_Sensor SDL_Sensor; |
||||
|
||||
/**
|
||||
* This is a unique ID for a sensor for the time it is connected to the system, |
||||
* and is never reused for the lifetime of the application. |
||||
* |
||||
* The ID value starts at 0 and increments from there. The value -1 is an invalid ID. |
||||
*/ |
||||
typedef Sint32 SDL_SensorID; |
||||
|
||||
/* The different sensors defined by SDL
|
||||
* |
||||
* Additional sensors may be available, using platform dependent semantics. |
||||
* |
||||
* Hare are the additional Android sensors: |
||||
* https://developer.android.com/reference/android/hardware/SensorEvent.html#values
|
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_SENSOR_INVALID = -1, /**< Returned for an invalid sensor */ |
||||
SDL_SENSOR_UNKNOWN, /**< Unknown sensor type */ |
||||
SDL_SENSOR_ACCEL, /**< Accelerometer */ |
||||
SDL_SENSOR_GYRO /**< Gyroscope */ |
||||
} SDL_SensorType; |
||||
|
||||
/**
|
||||
* Accelerometer sensor |
||||
* |
||||
* The accelerometer returns the current acceleration in SI meters per |
||||
* second squared. This includes gravity, so a device at rest will have |
||||
* an acceleration of SDL_STANDARD_GRAVITY straight down. |
||||
* |
||||
* values[0]: Acceleration on the x axis |
||||
* values[1]: Acceleration on the y axis |
||||
* values[2]: Acceleration on the z axis |
||||
* |
||||
* For phones held in portrait mode, the axes are defined as follows: |
||||
* -X ... +X : left ... right |
||||
* -Y ... +Y : bottom ... top |
||||
* -Z ... +Z : farther ... closer |
||||
*
|
||||
* The axis data is not changed when the phone is rotated. |
||||
* |
||||
* \sa SDL_GetDisplayOrientation() |
||||
*/ |
||||
#define SDL_STANDARD_GRAVITY 9.80665f |
||||
|
||||
/**
|
||||
* Gyroscope sensor |
||||
* |
||||
* The gyroscope returns the current rate of rotation in radians per second. |
||||
* The rotation is positive in the counter-clockwise direction. That is, |
||||
* an observer looking from a positive location on one of the axes would |
||||
* see positive rotation on that axis when it appeared to be rotating |
||||
* counter-clockwise. |
||||
* |
||||
* values[0]: Angular speed around the x axis |
||||
* values[1]: Angular speed around the y axis |
||||
* values[2]: Angular speed around the z axis |
||||
* |
||||
* For phones held in portrait mode, the axes are defined as follows: |
||||
* -X ... +X : left ... right |
||||
* -Y ... +Y : bottom ... top |
||||
* -Z ... +Z : farther ... closer |
||||
*
|
||||
* The axis data is not changed when the phone is rotated. |
||||
* |
||||
* \sa SDL_GetDisplayOrientation() |
||||
*/ |
||||
|
||||
/* Function prototypes */ |
||||
|
||||
/**
|
||||
* \brief Count the number of sensors attached to the system right now |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_NumSensors(void); |
||||
|
||||
/**
|
||||
* \brief Get the implementation dependent name of a sensor. |
||||
* |
||||
* This can be called before any sensors are opened. |
||||
*
|
||||
* \return The sensor name, or NULL if device_index is out of range. |
||||
*/ |
||||
extern DECLSPEC const char *SDLCALL SDL_SensorGetDeviceName(int device_index); |
||||
|
||||
/**
|
||||
* \brief Get the type of a sensor. |
||||
* |
||||
* This can be called before any sensors are opened. |
||||
* |
||||
* \return The sensor type, or SDL_SENSOR_INVALID if device_index is out of range. |
||||
*/ |
||||
extern DECLSPEC SDL_SensorType SDLCALL SDL_SensorGetDeviceType(int device_index); |
||||
|
||||
/**
|
||||
* \brief Get the platform dependent type of a sensor. |
||||
* |
||||
* This can be called before any sensors are opened. |
||||
* |
||||
* \return The sensor platform dependent type, or -1 if device_index is out of range. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SensorGetDeviceNonPortableType(int device_index); |
||||
|
||||
/**
|
||||
* \brief Get the instance ID of a sensor. |
||||
* |
||||
* This can be called before any sensors are opened. |
||||
* |
||||
* \return The sensor instance ID, or -1 if device_index is out of range. |
||||
*/ |
||||
extern DECLSPEC SDL_SensorID SDLCALL SDL_SensorGetDeviceInstanceID(int device_index); |
||||
|
||||
/**
|
||||
* \brief Open a sensor for use. |
||||
* |
||||
* The index passed as an argument refers to the N'th sensor on the system. |
||||
* |
||||
* \return A sensor identifier, or NULL if an error occurred. |
||||
*/ |
||||
extern DECLSPEC SDL_Sensor *SDLCALL SDL_SensorOpen(int device_index); |
||||
|
||||
/**
|
||||
* Return the SDL_Sensor associated with an instance id. |
||||
*/ |
||||
extern DECLSPEC SDL_Sensor *SDLCALL SDL_SensorFromInstanceID(SDL_SensorID instance_id); |
||||
|
||||
/**
|
||||
* \brief Get the implementation dependent name of a sensor. |
||||
* |
||||
* \return The sensor name, or NULL if the sensor is NULL. |
||||
*/ |
||||
extern DECLSPEC const char *SDLCALL SDL_SensorGetName(SDL_Sensor *sensor); |
||||
|
||||
/**
|
||||
* \brief Get the type of a sensor. |
||||
* |
||||
* This can be called before any sensors are opened. |
||||
* |
||||
* \return The sensor type, or SDL_SENSOR_INVALID if the sensor is NULL. |
||||
*/ |
||||
extern DECLSPEC SDL_SensorType SDLCALL SDL_SensorGetType(SDL_Sensor *sensor); |
||||
|
||||
/**
|
||||
* \brief Get the platform dependent type of a sensor. |
||||
* |
||||
* This can be called before any sensors are opened. |
||||
* |
||||
* \return The sensor platform dependent type, or -1 if the sensor is NULL. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SensorGetNonPortableType(SDL_Sensor *sensor); |
||||
|
||||
/**
|
||||
* \brief Get the instance ID of a sensor. |
||||
* |
||||
* This can be called before any sensors are opened. |
||||
* |
||||
* \return The sensor instance ID, or -1 if the sensor is NULL. |
||||
*/ |
||||
extern DECLSPEC SDL_SensorID SDLCALL SDL_SensorGetInstanceID(SDL_Sensor *sensor); |
||||
|
||||
/**
|
||||
* Get the current state of an opened sensor. |
||||
* |
||||
* The number of values and interpretation of the data is sensor dependent. |
||||
* |
||||
* \param sensor The sensor to query |
||||
* \param data A pointer filled with the current sensor state |
||||
* \param num_values The number of values to write to data |
||||
* |
||||
* \return 0 or -1 if an error occurred. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SensorGetData(SDL_Sensor * sensor, float *data, int num_values); |
||||
|
||||
/**
|
||||
* Close a sensor previously opened with SDL_SensorOpen() |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_SensorClose(SDL_Sensor * sensor); |
||||
|
||||
/**
|
||||
* Update the current state of the open sensors. |
||||
* |
||||
* This is called automatically by the event loop if sensor events are enabled. |
||||
* |
||||
* This needs to be called from the thread that initialized the sensor subsystem. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_SensorUpdate(void); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
/* *INDENT-OFF* */ |
||||
} |
||||
/* *INDENT-ON* */ |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_sensor_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,144 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
#ifndef SDL_shape_h_ |
||||
#define SDL_shape_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_pixels.h" |
||||
#include "SDL_rect.h" |
||||
#include "SDL_surface.h" |
||||
#include "SDL_video.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/** \file SDL_shape.h
|
||||
* |
||||
* Header file for the shaped window API. |
||||
*/ |
||||
|
||||
#define SDL_NONSHAPEABLE_WINDOW -1 |
||||
#define SDL_INVALID_SHAPE_ARGUMENT -2 |
||||
#define SDL_WINDOW_LACKS_SHAPE -3 |
||||
|
||||
/**
|
||||
* \brief Create a window that can be shaped with the specified position, dimensions, and flags. |
||||
* |
||||
* \param title The title of the window, in UTF-8 encoding. |
||||
* \param x The x position of the window, ::SDL_WINDOWPOS_CENTERED, or |
||||
* ::SDL_WINDOWPOS_UNDEFINED. |
||||
* \param y The y position of the window, ::SDL_WINDOWPOS_CENTERED, or |
||||
* ::SDL_WINDOWPOS_UNDEFINED. |
||||
* \param w The width of the window. |
||||
* \param h The height of the window. |
||||
* \param flags The flags for the window, a mask of SDL_WINDOW_BORDERLESS with any of the following: |
||||
* ::SDL_WINDOW_OPENGL, ::SDL_WINDOW_INPUT_GRABBED, |
||||
* ::SDL_WINDOW_HIDDEN, ::SDL_WINDOW_RESIZABLE, |
||||
* ::SDL_WINDOW_MAXIMIZED, ::SDL_WINDOW_MINIMIZED, |
||||
* ::SDL_WINDOW_BORDERLESS is always set, and ::SDL_WINDOW_FULLSCREEN is always unset. |
||||
* |
||||
* \return The window created, or NULL if window creation failed. |
||||
* |
||||
* \sa SDL_DestroyWindow() |
||||
*/ |
||||
extern DECLSPEC SDL_Window * SDLCALL SDL_CreateShapedWindow(const char *title,unsigned int x,unsigned int y,unsigned int w,unsigned int h,Uint32 flags); |
||||
|
||||
/**
|
||||
* \brief Return whether the given window is a shaped window. |
||||
* |
||||
* \param window The window to query for being shaped. |
||||
* |
||||
* \return SDL_TRUE if the window is a window that can be shaped, SDL_FALSE if the window is unshaped or NULL. |
||||
* |
||||
* \sa SDL_CreateShapedWindow |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_IsShapedWindow(const SDL_Window *window); |
||||
|
||||
/** \brief An enum denoting the specific type of contents present in an SDL_WindowShapeParams union. */ |
||||
typedef enum { |
||||
/** \brief The default mode, a binarized alpha cutoff of 1. */ |
||||
ShapeModeDefault, |
||||
/** \brief A binarized alpha cutoff with a given integer value. */ |
||||
ShapeModeBinarizeAlpha, |
||||
/** \brief A binarized alpha cutoff with a given integer value, but with the opposite comparison. */ |
||||
ShapeModeReverseBinarizeAlpha, |
||||
/** \brief A color key is applied. */ |
||||
ShapeModeColorKey |
||||
} WindowShapeMode; |
||||
|
||||
#define SDL_SHAPEMODEALPHA(mode) (mode == ShapeModeDefault || mode == ShapeModeBinarizeAlpha || mode == ShapeModeReverseBinarizeAlpha) |
||||
|
||||
/** \brief A union containing parameters for shaped windows. */ |
||||
typedef union { |
||||
/** \brief A cutoff alpha value for binarization of the window shape's alpha channel. */ |
||||
Uint8 binarizationCutoff; |
||||
SDL_Color colorKey; |
||||
} SDL_WindowShapeParams; |
||||
|
||||
/** \brief A struct that tags the SDL_WindowShapeParams union with an enum describing the type of its contents. */ |
||||
typedef struct SDL_WindowShapeMode { |
||||
/** \brief The mode of these window-shape parameters. */ |
||||
WindowShapeMode mode; |
||||
/** \brief Window-shape parameters. */ |
||||
SDL_WindowShapeParams parameters; |
||||
} SDL_WindowShapeMode; |
||||
|
||||
/**
|
||||
* \brief Set the shape and parameters of a shaped window. |
||||
* |
||||
* \param window The shaped window whose parameters should be set. |
||||
* \param shape A surface encoding the desired shape for the window. |
||||
* \param shape_mode The parameters to set for the shaped window. |
||||
* |
||||
* \return 0 on success, SDL_INVALID_SHAPE_ARGUMENT on an invalid shape argument, or SDL_NONSHAPEABLE_WINDOW |
||||
* if the SDL_Window given does not reference a valid shaped window. |
||||
* |
||||
* \sa SDL_WindowShapeMode |
||||
* \sa SDL_GetShapedWindowMode. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SetWindowShape(SDL_Window *window,SDL_Surface *shape,SDL_WindowShapeMode *shape_mode); |
||||
|
||||
/**
|
||||
* \brief Get the shape parameters of a shaped window. |
||||
* |
||||
* \param window The shaped window whose parameters should be retrieved. |
||||
* \param shape_mode An empty shape-mode structure to fill, or NULL to check whether the window has a shape. |
||||
* |
||||
* \return 0 if the window has a shape and, provided shape_mode was not NULL, shape_mode has been filled with the mode |
||||
* data, SDL_NONSHAPEABLE_WINDOW if the SDL_Window given is not a shaped window, or SDL_WINDOW_LACKS_SHAPE if |
||||
* the SDL_Window given is a shapeable window currently lacking a shape. |
||||
* |
||||
* \sa SDL_WindowShapeMode |
||||
* \sa SDL_SetWindowShape |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GetShapedWindowMode(SDL_Window *window,SDL_WindowShapeMode *shape_mode); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_shape_h_ */ |
||||
@ -0,0 +1,607 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_stdinc.h |
||||
* |
||||
* This is a general header that includes C language support. |
||||
*/ |
||||
|
||||
#ifndef SDL_stdinc_h_ |
||||
#define SDL_stdinc_h_ |
||||
|
||||
#include "SDL_config.h" |
||||
|
||||
#ifdef HAVE_SYS_TYPES_H |
||||
#include <sys/types.h> |
||||
#endif |
||||
#ifdef HAVE_STDIO_H |
||||
#include <stdio.h> |
||||
#endif |
||||
#if defined(STDC_HEADERS) |
||||
# include <stdlib.h> |
||||
# include <stddef.h> |
||||
# include <stdarg.h> |
||||
#else |
||||
# if defined(HAVE_STDLIB_H) |
||||
# include <stdlib.h> |
||||
# elif defined(HAVE_MALLOC_H) |
||||
# include <malloc.h> |
||||
# endif |
||||
# if defined(HAVE_STDDEF_H) |
||||
# include <stddef.h> |
||||
# endif |
||||
# if defined(HAVE_STDARG_H) |
||||
# include <stdarg.h> |
||||
# endif |
||||
#endif |
||||
#ifdef HAVE_STRING_H |
||||
# if !defined(STDC_HEADERS) && defined(HAVE_MEMORY_H) |
||||
# include <memory.h> |
||||
# endif |
||||
# include <string.h> |
||||
#endif |
||||
#ifdef HAVE_STRINGS_H |
||||
# include <strings.h> |
||||
#endif |
||||
#ifdef HAVE_WCHAR_H |
||||
# include <wchar.h> |
||||
#endif |
||||
#if defined(HAVE_INTTYPES_H) |
||||
# include <inttypes.h> |
||||
#elif defined(HAVE_STDINT_H) |
||||
# include <stdint.h> |
||||
#endif |
||||
#ifdef HAVE_CTYPE_H |
||||
# include <ctype.h> |
||||
#endif |
||||
#ifdef HAVE_MATH_H |
||||
# if defined(__WINRT__) |
||||
/* Defining _USE_MATH_DEFINES is required to get M_PI to be defined on
|
||||
WinRT. See http://msdn.microsoft.com/en-us/library/4hwaceh6.aspx
|
||||
for more information. |
||||
*/ |
||||
# define _USE_MATH_DEFINES |
||||
# endif |
||||
# include <math.h> |
||||
#endif |
||||
#ifdef HAVE_FLOAT_H |
||||
# include <float.h> |
||||
#endif |
||||
#if defined(HAVE_ALLOCA) && !defined(alloca) |
||||
# if defined(HAVE_ALLOCA_H) |
||||
# include <alloca.h> |
||||
# elif defined(__GNUC__) |
||||
# define alloca __builtin_alloca |
||||
# elif defined(_MSC_VER) |
||||
# include <malloc.h> |
||||
# define alloca _alloca |
||||
# elif defined(__WATCOMC__) |
||||
# include <malloc.h> |
||||
# elif defined(__BORLANDC__) |
||||
# include <malloc.h> |
||||
# elif defined(__DMC__) |
||||
# include <stdlib.h> |
||||
# elif defined(__AIX__) |
||||
#pragma alloca |
||||
# elif defined(__MRC__) |
||||
void *alloca(unsigned); |
||||
# else |
||||
char *alloca(); |
||||
# endif |
||||
#endif |
||||
|
||||
/**
|
||||
* The number of elements in an array. |
||||
*/ |
||||
#define SDL_arraysize(array) (sizeof(array)/sizeof(array[0])) |
||||
#define SDL_TABLESIZE(table) SDL_arraysize(table) |
||||
|
||||
/**
|
||||
* Macro useful for building other macros with strings in them |
||||
* |
||||
* e.g. #define LOG_ERROR(X) OutputDebugString(SDL_STRINGIFY_ARG(__FUNCTION__) ": " X "\n") |
||||
*/ |
||||
#define SDL_STRINGIFY_ARG(arg) #arg |
||||
|
||||
/**
|
||||
* \name Cast operators |
||||
* |
||||
* Use proper C++ casts when compiled as C++ to be compatible with the option |
||||
* -Wold-style-cast of GCC (and -Werror=old-style-cast in GCC 4.2 and above). |
||||
*/ |
||||
/* @{ */ |
||||
#ifdef __cplusplus |
||||
#define SDL_reinterpret_cast(type, expression) reinterpret_cast<type>(expression) |
||||
#define SDL_static_cast(type, expression) static_cast<type>(expression) |
||||
#define SDL_const_cast(type, expression) const_cast<type>(expression) |
||||
#else |
||||
#define SDL_reinterpret_cast(type, expression) ((type)(expression)) |
||||
#define SDL_static_cast(type, expression) ((type)(expression)) |
||||
#define SDL_const_cast(type, expression) ((type)(expression)) |
||||
#endif |
||||
/* @} *//* Cast operators */ |
||||
|
||||
/* Define a four character code as a Uint32 */ |
||||
#define SDL_FOURCC(A, B, C, D) \ |
||||
((SDL_static_cast(Uint32, SDL_static_cast(Uint8, (A))) << 0) | \
|
||||
(SDL_static_cast(Uint32, SDL_static_cast(Uint8, (B))) << 8) | \
|
||||
(SDL_static_cast(Uint32, SDL_static_cast(Uint8, (C))) << 16) | \
|
||||
(SDL_static_cast(Uint32, SDL_static_cast(Uint8, (D))) << 24)) |
||||
|
||||
/**
|
||||
* \name Basic data types |
||||
*/ |
||||
/* @{ */ |
||||
|
||||
#ifdef __CC_ARM |
||||
/* ARM's compiler throws warnings if we use an enum: like "SDL_bool x = a < b;" */ |
||||
#define SDL_FALSE 0 |
||||
#define SDL_TRUE 1 |
||||
typedef int SDL_bool; |
||||
#else |
||||
typedef enum |
||||
{ |
||||
SDL_FALSE = 0, |
||||
SDL_TRUE = 1 |
||||
} SDL_bool; |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief A signed 8-bit integer type. |
||||
*/ |
||||
#define SDL_MAX_SINT8 ((Sint8)0x7F) /* 127 */ |
||||
#define SDL_MIN_SINT8 ((Sint8)(~0x7F)) /* -128 */ |
||||
typedef int8_t Sint8; |
||||
/**
|
||||
* \brief An unsigned 8-bit integer type. |
||||
*/ |
||||
#define SDL_MAX_UINT8 ((Uint8)0xFF) /* 255 */ |
||||
#define SDL_MIN_UINT8 ((Uint8)0x00) /* 0 */ |
||||
typedef uint8_t Uint8; |
||||
/**
|
||||
* \brief A signed 16-bit integer type. |
||||
*/ |
||||
#define SDL_MAX_SINT16 ((Sint16)0x7FFF) /* 32767 */ |
||||
#define SDL_MIN_SINT16 ((Sint16)(~0x7FFF)) /* -32768 */ |
||||
typedef int16_t Sint16; |
||||
/**
|
||||
* \brief An unsigned 16-bit integer type. |
||||
*/ |
||||
#define SDL_MAX_UINT16 ((Uint16)0xFFFF) /* 65535 */ |
||||
#define SDL_MIN_UINT16 ((Uint16)0x0000) /* 0 */ |
||||
typedef uint16_t Uint16; |
||||
/**
|
||||
* \brief A signed 32-bit integer type. |
||||
*/ |
||||
#define SDL_MAX_SINT32 ((Sint32)0x7FFFFFFF) /* 2147483647 */ |
||||
#define SDL_MIN_SINT32 ((Sint32)(~0x7FFFFFFF)) /* -2147483648 */ |
||||
typedef int32_t Sint32; |
||||
/**
|
||||
* \brief An unsigned 32-bit integer type. |
||||
*/ |
||||
#define SDL_MAX_UINT32 ((Uint32)0xFFFFFFFFu) /* 4294967295 */ |
||||
#define SDL_MIN_UINT32 ((Uint32)0x00000000) /* 0 */ |
||||
typedef uint32_t Uint32; |
||||
|
||||
/**
|
||||
* \brief A signed 64-bit integer type. |
||||
*/ |
||||
#define SDL_MAX_SINT64 ((Sint64)0x7FFFFFFFFFFFFFFFll) /* 9223372036854775807 */ |
||||
#define SDL_MIN_SINT64 ((Sint64)(~0x7FFFFFFFFFFFFFFFll)) /* -9223372036854775808 */ |
||||
typedef int64_t Sint64; |
||||
/**
|
||||
* \brief An unsigned 64-bit integer type. |
||||
*/ |
||||
#define SDL_MAX_UINT64 ((Uint64)0xFFFFFFFFFFFFFFFFull) /* 18446744073709551615 */ |
||||
#define SDL_MIN_UINT64 ((Uint64)(0x0000000000000000ull)) /* 0 */ |
||||
typedef uint64_t Uint64; |
||||
|
||||
/* @} *//* Basic data types */ |
||||
|
||||
/* Make sure we have macros for printing 64 bit values.
|
||||
* <stdint.h> should define these but this is not true all platforms. |
||||
* (for example win32) */ |
||||
#ifndef SDL_PRIs64 |
||||
#ifdef PRIs64 |
||||
#define SDL_PRIs64 PRIs64 |
||||
#elif defined(__WIN32__) |
||||
#define SDL_PRIs64 "I64d" |
||||
#elif defined(__LINUX__) && defined(__LP64__) |
||||
#define SDL_PRIs64 "ld" |
||||
#else |
||||
#define SDL_PRIs64 "lld" |
||||
#endif |
||||
#endif |
||||
#ifndef SDL_PRIu64 |
||||
#ifdef PRIu64 |
||||
#define SDL_PRIu64 PRIu64 |
||||
#elif defined(__WIN32__) |
||||
#define SDL_PRIu64 "I64u" |
||||
#elif defined(__LINUX__) && defined(__LP64__) |
||||
#define SDL_PRIu64 "lu" |
||||
#else |
||||
#define SDL_PRIu64 "llu" |
||||
#endif |
||||
#endif |
||||
#ifndef SDL_PRIx64 |
||||
#ifdef PRIx64 |
||||
#define SDL_PRIx64 PRIx64 |
||||
#elif defined(__WIN32__) |
||||
#define SDL_PRIx64 "I64x" |
||||
#elif defined(__LINUX__) && defined(__LP64__) |
||||
#define SDL_PRIx64 "lx" |
||||
#else |
||||
#define SDL_PRIx64 "llx" |
||||
#endif |
||||
#endif |
||||
#ifndef SDL_PRIX64 |
||||
#ifdef PRIX64 |
||||
#define SDL_PRIX64 PRIX64 |
||||
#elif defined(__WIN32__) |
||||
#define SDL_PRIX64 "I64X" |
||||
#elif defined(__LINUX__) && defined(__LP64__) |
||||
#define SDL_PRIX64 "lX" |
||||
#else |
||||
#define SDL_PRIX64 "llX" |
||||
#endif |
||||
#endif |
||||
|
||||
/* Annotations to help code analysis tools */ |
||||
#ifdef SDL_DISABLE_ANALYZE_MACROS |
||||
#define SDL_IN_BYTECAP(x) |
||||
#define SDL_INOUT_Z_CAP(x) |
||||
#define SDL_OUT_Z_CAP(x) |
||||
#define SDL_OUT_CAP(x) |
||||
#define SDL_OUT_BYTECAP(x) |
||||
#define SDL_OUT_Z_BYTECAP(x) |
||||
#define SDL_PRINTF_FORMAT_STRING |
||||
#define SDL_SCANF_FORMAT_STRING |
||||
#define SDL_PRINTF_VARARG_FUNC( fmtargnumber ) |
||||
#define SDL_SCANF_VARARG_FUNC( fmtargnumber ) |
||||
#else |
||||
#if defined(_MSC_VER) && (_MSC_VER >= 1600) /* VS 2010 and above */ |
||||
#include <sal.h> |
||||
|
||||
#define SDL_IN_BYTECAP(x) _In_bytecount_(x) |
||||
#define SDL_INOUT_Z_CAP(x) _Inout_z_cap_(x) |
||||
#define SDL_OUT_Z_CAP(x) _Out_z_cap_(x) |
||||
#define SDL_OUT_CAP(x) _Out_cap_(x) |
||||
#define SDL_OUT_BYTECAP(x) _Out_bytecap_(x) |
||||
#define SDL_OUT_Z_BYTECAP(x) _Out_z_bytecap_(x) |
||||
|
||||
#define SDL_PRINTF_FORMAT_STRING _Printf_format_string_ |
||||
#define SDL_SCANF_FORMAT_STRING _Scanf_format_string_impl_ |
||||
#else |
||||
#define SDL_IN_BYTECAP(x) |
||||
#define SDL_INOUT_Z_CAP(x) |
||||
#define SDL_OUT_Z_CAP(x) |
||||
#define SDL_OUT_CAP(x) |
||||
#define SDL_OUT_BYTECAP(x) |
||||
#define SDL_OUT_Z_BYTECAP(x) |
||||
#define SDL_PRINTF_FORMAT_STRING |
||||
#define SDL_SCANF_FORMAT_STRING |
||||
#endif |
||||
#if defined(__GNUC__) |
||||
#define SDL_PRINTF_VARARG_FUNC( fmtargnumber ) __attribute__ (( format( __printf__, fmtargnumber, fmtargnumber+1 ))) |
||||
#define SDL_SCANF_VARARG_FUNC( fmtargnumber ) __attribute__ (( format( __scanf__, fmtargnumber, fmtargnumber+1 ))) |
||||
#else |
||||
#define SDL_PRINTF_VARARG_FUNC( fmtargnumber ) |
||||
#define SDL_SCANF_VARARG_FUNC( fmtargnumber ) |
||||
#endif |
||||
#endif /* SDL_DISABLE_ANALYZE_MACROS */ |
||||
|
||||
#define SDL_COMPILE_TIME_ASSERT(name, x) \ |
||||
typedef int SDL_compile_time_assert_ ## name[(x) * 2 - 1] |
||||
/** \cond */ |
||||
#ifndef DOXYGEN_SHOULD_IGNORE_THIS |
||||
SDL_COMPILE_TIME_ASSERT(uint8, sizeof(Uint8) == 1); |
||||
SDL_COMPILE_TIME_ASSERT(sint8, sizeof(Sint8) == 1); |
||||
SDL_COMPILE_TIME_ASSERT(uint16, sizeof(Uint16) == 2); |
||||
SDL_COMPILE_TIME_ASSERT(sint16, sizeof(Sint16) == 2); |
||||
SDL_COMPILE_TIME_ASSERT(uint32, sizeof(Uint32) == 4); |
||||
SDL_COMPILE_TIME_ASSERT(sint32, sizeof(Sint32) == 4); |
||||
SDL_COMPILE_TIME_ASSERT(uint64, sizeof(Uint64) == 8); |
||||
SDL_COMPILE_TIME_ASSERT(sint64, sizeof(Sint64) == 8); |
||||
#endif /* DOXYGEN_SHOULD_IGNORE_THIS */ |
||||
/** \endcond */ |
||||
|
||||
/* Check to make sure enums are the size of ints, for structure packing.
|
||||
For both Watcom C/C++ and Borland C/C++ the compiler option that makes |
||||
enums having the size of an int must be enabled. |
||||
This is "-b" for Borland C/C++ and "-ei" for Watcom C/C++ (v11). |
||||
*/ |
||||
|
||||
/** \cond */ |
||||
#ifndef DOXYGEN_SHOULD_IGNORE_THIS |
||||
#if !defined(__ANDROID__) |
||||
/* TODO: include/SDL_stdinc.h:174: error: size of array 'SDL_dummy_enum' is negative */ |
||||
typedef enum |
||||
{ |
||||
DUMMY_ENUM_VALUE |
||||
} SDL_DUMMY_ENUM; |
||||
|
||||
SDL_COMPILE_TIME_ASSERT(enum, sizeof(SDL_DUMMY_ENUM) == sizeof(int)); |
||||
#endif |
||||
#endif /* DOXYGEN_SHOULD_IGNORE_THIS */ |
||||
/** \endcond */ |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
#ifdef HAVE_ALLOCA |
||||
#define SDL_stack_alloc(type, count) (type*)alloca(sizeof(type)*(count)) |
||||
#define SDL_stack_free(data) |
||||
#else |
||||
#define SDL_stack_alloc(type, count) (type*)SDL_malloc(sizeof(type)*(count)) |
||||
#define SDL_stack_free(data) SDL_free(data) |
||||
#endif |
||||
|
||||
extern DECLSPEC void *SDLCALL SDL_malloc(size_t size); |
||||
extern DECLSPEC void *SDLCALL SDL_calloc(size_t nmemb, size_t size); |
||||
extern DECLSPEC void *SDLCALL SDL_realloc(void *mem, size_t size); |
||||
extern DECLSPEC void SDLCALL SDL_free(void *mem); |
||||
|
||||
typedef void *(SDLCALL *SDL_malloc_func)(size_t size); |
||||
typedef void *(SDLCALL *SDL_calloc_func)(size_t nmemb, size_t size); |
||||
typedef void *(SDLCALL *SDL_realloc_func)(void *mem, size_t size); |
||||
typedef void (SDLCALL *SDL_free_func)(void *mem); |
||||
|
||||
/**
|
||||
* \brief Get the current set of SDL memory functions |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_GetMemoryFunctions(SDL_malloc_func *malloc_func, |
||||
SDL_calloc_func *calloc_func, |
||||
SDL_realloc_func *realloc_func, |
||||
SDL_free_func *free_func); |
||||
|
||||
/**
|
||||
* \brief Replace SDL's memory allocation functions with a custom set |
||||
* |
||||
* \note If you are replacing SDL's memory functions, you should call |
||||
* SDL_GetNumAllocations() and be very careful if it returns non-zero. |
||||
* That means that your free function will be called with memory |
||||
* allocated by the previous memory allocation functions. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SetMemoryFunctions(SDL_malloc_func malloc_func, |
||||
SDL_calloc_func calloc_func, |
||||
SDL_realloc_func realloc_func, |
||||
SDL_free_func free_func); |
||||
|
||||
/**
|
||||
* \brief Get the number of outstanding (unfreed) allocations |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GetNumAllocations(void); |
||||
|
||||
extern DECLSPEC char *SDLCALL SDL_getenv(const char *name); |
||||
extern DECLSPEC int SDLCALL SDL_setenv(const char *name, const char *value, int overwrite); |
||||
|
||||
extern DECLSPEC void SDLCALL SDL_qsort(void *base, size_t nmemb, size_t size, int (*compare) (const void *, const void *)); |
||||
|
||||
extern DECLSPEC int SDLCALL SDL_abs(int x); |
||||
|
||||
/* !!! FIXME: these have side effects. You probably shouldn't use them. */ |
||||
/* !!! FIXME: Maybe we do forceinline functions of SDL_mini, SDL_minf, etc? */ |
||||
#define SDL_min(x, y) (((x) < (y)) ? (x) : (y)) |
||||
#define SDL_max(x, y) (((x) > (y)) ? (x) : (y)) |
||||
|
||||
extern DECLSPEC int SDLCALL SDL_isdigit(int x); |
||||
extern DECLSPEC int SDLCALL SDL_isspace(int x); |
||||
extern DECLSPEC int SDLCALL SDL_toupper(int x); |
||||
extern DECLSPEC int SDLCALL SDL_tolower(int x); |
||||
|
||||
extern DECLSPEC void *SDLCALL SDL_memset(SDL_OUT_BYTECAP(len) void *dst, int c, size_t len); |
||||
|
||||
#define SDL_zero(x) SDL_memset(&(x), 0, sizeof((x))) |
||||
#define SDL_zerop(x) SDL_memset((x), 0, sizeof(*(x))) |
||||
|
||||
/* Note that memset() is a byte assignment and this is a 32-bit assignment, so they're not directly equivalent. */ |
||||
SDL_FORCE_INLINE void SDL_memset4(void *dst, Uint32 val, size_t dwords) |
||||
{ |
||||
#if defined(__GNUC__) && defined(i386) |
||||
int u0, u1, u2; |
||||
__asm__ __volatile__ ( |
||||
"cld \n\t" |
||||
"rep ; stosl \n\t" |
||||
: "=&D" (u0), "=&a" (u1), "=&c" (u2) |
||||
: "0" (dst), "1" (val), "2" (SDL_static_cast(Uint32, dwords)) |
||||
: "memory" |
||||
); |
||||
#else |
||||
size_t _n = (dwords + 3) / 4; |
||||
Uint32 *_p = SDL_static_cast(Uint32 *, dst); |
||||
Uint32 _val = (val); |
||||
if (dwords == 0) |
||||
return; |
||||
switch (dwords % 4) |
||||
{ |
||||
case 0: do { *_p++ = _val; /* fallthrough */ |
||||
case 3: *_p++ = _val; /* fallthrough */ |
||||
case 2: *_p++ = _val; /* fallthrough */ |
||||
case 1: *_p++ = _val; /* fallthrough */ |
||||
} while ( --_n ); |
||||
} |
||||
#endif |
||||
} |
||||
|
||||
extern DECLSPEC void *SDLCALL SDL_memcpy(SDL_OUT_BYTECAP(len) void *dst, SDL_IN_BYTECAP(len) const void *src, size_t len); |
||||
|
||||
extern DECLSPEC void *SDLCALL SDL_memmove(SDL_OUT_BYTECAP(len) void *dst, SDL_IN_BYTECAP(len) const void *src, size_t len); |
||||
extern DECLSPEC int SDLCALL SDL_memcmp(const void *s1, const void *s2, size_t len); |
||||
|
||||
extern DECLSPEC wchar_t *SDLCALL SDL_wcsdup(const wchar_t *wstr); |
||||
extern DECLSPEC size_t SDLCALL SDL_wcslen(const wchar_t *wstr); |
||||
extern DECLSPEC size_t SDLCALL SDL_wcslcpy(SDL_OUT_Z_CAP(maxlen) wchar_t *dst, const wchar_t *src, size_t maxlen); |
||||
extern DECLSPEC size_t SDLCALL SDL_wcslcat(SDL_INOUT_Z_CAP(maxlen) wchar_t *dst, const wchar_t *src, size_t maxlen); |
||||
extern DECLSPEC int SDLCALL SDL_wcscmp(const wchar_t *str1, const wchar_t *str2); |
||||
|
||||
extern DECLSPEC size_t SDLCALL SDL_strlen(const char *str); |
||||
extern DECLSPEC size_t SDLCALL SDL_strlcpy(SDL_OUT_Z_CAP(maxlen) char *dst, const char *src, size_t maxlen); |
||||
extern DECLSPEC size_t SDLCALL SDL_utf8strlcpy(SDL_OUT_Z_CAP(dst_bytes) char *dst, const char *src, size_t dst_bytes); |
||||
extern DECLSPEC size_t SDLCALL SDL_strlcat(SDL_INOUT_Z_CAP(maxlen) char *dst, const char *src, size_t maxlen); |
||||
extern DECLSPEC char *SDLCALL SDL_strdup(const char *str); |
||||
extern DECLSPEC char *SDLCALL SDL_strrev(char *str); |
||||
extern DECLSPEC char *SDLCALL SDL_strupr(char *str); |
||||
extern DECLSPEC char *SDLCALL SDL_strlwr(char *str); |
||||
extern DECLSPEC char *SDLCALL SDL_strchr(const char *str, int c); |
||||
extern DECLSPEC char *SDLCALL SDL_strrchr(const char *str, int c); |
||||
extern DECLSPEC char *SDLCALL SDL_strstr(const char *haystack, const char *needle); |
||||
extern DECLSPEC size_t SDLCALL SDL_utf8strlen(const char *str); |
||||
|
||||
extern DECLSPEC char *SDLCALL SDL_itoa(int value, char *str, int radix); |
||||
extern DECLSPEC char *SDLCALL SDL_uitoa(unsigned int value, char *str, int radix); |
||||
extern DECLSPEC char *SDLCALL SDL_ltoa(long value, char *str, int radix); |
||||
extern DECLSPEC char *SDLCALL SDL_ultoa(unsigned long value, char *str, int radix); |
||||
extern DECLSPEC char *SDLCALL SDL_lltoa(Sint64 value, char *str, int radix); |
||||
extern DECLSPEC char *SDLCALL SDL_ulltoa(Uint64 value, char *str, int radix); |
||||
|
||||
extern DECLSPEC int SDLCALL SDL_atoi(const char *str); |
||||
extern DECLSPEC double SDLCALL SDL_atof(const char *str); |
||||
extern DECLSPEC long SDLCALL SDL_strtol(const char *str, char **endp, int base); |
||||
extern DECLSPEC unsigned long SDLCALL SDL_strtoul(const char *str, char **endp, int base); |
||||
extern DECLSPEC Sint64 SDLCALL SDL_strtoll(const char *str, char **endp, int base); |
||||
extern DECLSPEC Uint64 SDLCALL SDL_strtoull(const char *str, char **endp, int base); |
||||
extern DECLSPEC double SDLCALL SDL_strtod(const char *str, char **endp); |
||||
|
||||
extern DECLSPEC int SDLCALL SDL_strcmp(const char *str1, const char *str2); |
||||
extern DECLSPEC int SDLCALL SDL_strncmp(const char *str1, const char *str2, size_t maxlen); |
||||
extern DECLSPEC int SDLCALL SDL_strcasecmp(const char *str1, const char *str2); |
||||
extern DECLSPEC int SDLCALL SDL_strncasecmp(const char *str1, const char *str2, size_t len); |
||||
|
||||
extern DECLSPEC int SDLCALL SDL_sscanf(const char *text, SDL_SCANF_FORMAT_STRING const char *fmt, ...) SDL_SCANF_VARARG_FUNC(2); |
||||
extern DECLSPEC int SDLCALL SDL_vsscanf(const char *text, const char *fmt, va_list ap); |
||||
extern DECLSPEC int SDLCALL SDL_snprintf(SDL_OUT_Z_CAP(maxlen) char *text, size_t maxlen, SDL_PRINTF_FORMAT_STRING const char *fmt, ... ) SDL_PRINTF_VARARG_FUNC(3); |
||||
extern DECLSPEC int SDLCALL SDL_vsnprintf(SDL_OUT_Z_CAP(maxlen) char *text, size_t maxlen, const char *fmt, va_list ap); |
||||
|
||||
#ifndef HAVE_M_PI |
||||
#ifndef M_PI |
||||
#define M_PI 3.14159265358979323846264338327950288 /**< pi */ |
||||
#endif |
||||
#endif |
||||
|
||||
extern DECLSPEC double SDLCALL SDL_acos(double x); |
||||
extern DECLSPEC float SDLCALL SDL_acosf(float x); |
||||
extern DECLSPEC double SDLCALL SDL_asin(double x); |
||||
extern DECLSPEC float SDLCALL SDL_asinf(float x); |
||||
extern DECLSPEC double SDLCALL SDL_atan(double x); |
||||
extern DECLSPEC float SDLCALL SDL_atanf(float x); |
||||
extern DECLSPEC double SDLCALL SDL_atan2(double x, double y); |
||||
extern DECLSPEC float SDLCALL SDL_atan2f(float x, float y); |
||||
extern DECLSPEC double SDLCALL SDL_ceil(double x); |
||||
extern DECLSPEC float SDLCALL SDL_ceilf(float x); |
||||
extern DECLSPEC double SDLCALL SDL_copysign(double x, double y); |
||||
extern DECLSPEC float SDLCALL SDL_copysignf(float x, float y); |
||||
extern DECLSPEC double SDLCALL SDL_cos(double x); |
||||
extern DECLSPEC float SDLCALL SDL_cosf(float x); |
||||
extern DECLSPEC double SDLCALL SDL_exp(double x); |
||||
extern DECLSPEC float SDLCALL SDL_expf(float x); |
||||
extern DECLSPEC double SDLCALL SDL_fabs(double x); |
||||
extern DECLSPEC float SDLCALL SDL_fabsf(float x); |
||||
extern DECLSPEC double SDLCALL SDL_floor(double x); |
||||
extern DECLSPEC float SDLCALL SDL_floorf(float x); |
||||
extern DECLSPEC double SDLCALL SDL_fmod(double x, double y); |
||||
extern DECLSPEC float SDLCALL SDL_fmodf(float x, float y); |
||||
extern DECLSPEC double SDLCALL SDL_log(double x); |
||||
extern DECLSPEC float SDLCALL SDL_logf(float x); |
||||
extern DECLSPEC double SDLCALL SDL_log10(double x); |
||||
extern DECLSPEC float SDLCALL SDL_log10f(float x); |
||||
extern DECLSPEC double SDLCALL SDL_pow(double x, double y); |
||||
extern DECLSPEC float SDLCALL SDL_powf(float x, float y); |
||||
extern DECLSPEC double SDLCALL SDL_scalbn(double x, int n); |
||||
extern DECLSPEC float SDLCALL SDL_scalbnf(float x, int n); |
||||
extern DECLSPEC double SDLCALL SDL_sin(double x); |
||||
extern DECLSPEC float SDLCALL SDL_sinf(float x); |
||||
extern DECLSPEC double SDLCALL SDL_sqrt(double x); |
||||
extern DECLSPEC float SDLCALL SDL_sqrtf(float x); |
||||
extern DECLSPEC double SDLCALL SDL_tan(double x); |
||||
extern DECLSPEC float SDLCALL SDL_tanf(float x); |
||||
|
||||
/* The SDL implementation of iconv() returns these error codes */ |
||||
#define SDL_ICONV_ERROR (size_t)-1 |
||||
#define SDL_ICONV_E2BIG (size_t)-2 |
||||
#define SDL_ICONV_EILSEQ (size_t)-3 |
||||
#define SDL_ICONV_EINVAL (size_t)-4 |
||||
|
||||
/* SDL_iconv_* are now always real symbols/types, not macros or inlined. */ |
||||
typedef struct _SDL_iconv_t *SDL_iconv_t; |
||||
extern DECLSPEC SDL_iconv_t SDLCALL SDL_iconv_open(const char *tocode, |
||||
const char *fromcode); |
||||
extern DECLSPEC int SDLCALL SDL_iconv_close(SDL_iconv_t cd); |
||||
extern DECLSPEC size_t SDLCALL SDL_iconv(SDL_iconv_t cd, const char **inbuf, |
||||
size_t * inbytesleft, char **outbuf, |
||||
size_t * outbytesleft); |
||||
/**
|
||||
* This function converts a string between encodings in one pass, returning a |
||||
* string that must be freed with SDL_free() or NULL on error. |
||||
*/ |
||||
extern DECLSPEC char *SDLCALL SDL_iconv_string(const char *tocode, |
||||
const char *fromcode, |
||||
const char *inbuf, |
||||
size_t inbytesleft); |
||||
#define SDL_iconv_utf8_locale(S) SDL_iconv_string("", "UTF-8", S, SDL_strlen(S)+1) |
||||
#define SDL_iconv_utf8_ucs2(S) (Uint16 *)SDL_iconv_string("UCS-2-INTERNAL", "UTF-8", S, SDL_strlen(S)+1) |
||||
#define SDL_iconv_utf8_ucs4(S) (Uint32 *)SDL_iconv_string("UCS-4-INTERNAL", "UTF-8", S, SDL_strlen(S)+1) |
||||
|
||||
/* force builds using Clang's static analysis tools to use literal C runtime
|
||||
here, since there are possibly tests that are ineffective otherwise. */ |
||||
#if defined(__clang_analyzer__) && !defined(SDL_DISABLE_ANALYZE_MACROS) |
||||
#define SDL_malloc malloc |
||||
#define SDL_calloc calloc |
||||
#define SDL_realloc realloc |
||||
#define SDL_free free |
||||
#define SDL_memset memset |
||||
#define SDL_memcpy memcpy |
||||
#define SDL_memmove memmove |
||||
#define SDL_memcmp memcmp |
||||
#define SDL_strlen strlen |
||||
#define SDL_strlcpy strlcpy |
||||
#define SDL_strlcat strlcat |
||||
#define SDL_strdup strdup |
||||
#define SDL_strchr strchr |
||||
#define SDL_strrchr strrchr |
||||
#define SDL_strstr strstr |
||||
#define SDL_strcmp strcmp |
||||
#define SDL_strncmp strncmp |
||||
#define SDL_strcasecmp strcasecmp |
||||
#define SDL_strncasecmp strncasecmp |
||||
#define SDL_sscanf sscanf |
||||
#define SDL_vsscanf vsscanf |
||||
#define SDL_snprintf snprintf |
||||
#define SDL_vsnprintf vsnprintf |
||||
#endif |
||||
|
||||
SDL_FORCE_INLINE void *SDL_memcpy4(SDL_OUT_BYTECAP(dwords*4) void *dst, SDL_IN_BYTECAP(dwords*4) const void *src, size_t dwords) |
||||
{ |
||||
return SDL_memcpy(dst, src, dwords * 4); |
||||
} |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_stdinc_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,554 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_surface.h |
||||
* |
||||
* Header file for ::SDL_Surface definition and management functions. |
||||
*/ |
||||
|
||||
#ifndef SDL_surface_h_ |
||||
#define SDL_surface_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_pixels.h" |
||||
#include "SDL_rect.h" |
||||
#include "SDL_blendmode.h" |
||||
#include "SDL_rwops.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \name Surface flags |
||||
* |
||||
* These are the currently supported flags for the ::SDL_Surface. |
||||
* |
||||
* \internal |
||||
* Used internally (read-only). |
||||
*/ |
||||
/* @{ */ |
||||
#define SDL_SWSURFACE 0 /**< Just here for compatibility */ |
||||
#define SDL_PREALLOC 0x00000001 /**< Surface uses preallocated memory */ |
||||
#define SDL_RLEACCEL 0x00000002 /**< Surface is RLE encoded */ |
||||
#define SDL_DONTFREE 0x00000004 /**< Surface is referenced internally */ |
||||
#define SDL_SIMD_ALIGNED 0x00000008 /**< Surface uses aligned memory */ |
||||
/* @} *//* Surface flags */ |
||||
|
||||
/**
|
||||
* Evaluates to true if the surface needs to be locked before access. |
||||
*/ |
||||
#define SDL_MUSTLOCK(S) (((S)->flags & SDL_RLEACCEL) != 0) |
||||
|
||||
/**
|
||||
* \brief A collection of pixels used in software blitting. |
||||
* |
||||
* \note This structure should be treated as read-only, except for \c pixels, |
||||
* which, if not NULL, contains the raw pixel data for the surface. |
||||
*/ |
||||
typedef struct SDL_Surface |
||||
{ |
||||
Uint32 flags; /**< Read-only */ |
||||
SDL_PixelFormat *format; /**< Read-only */ |
||||
int w, h; /**< Read-only */ |
||||
int pitch; /**< Read-only */ |
||||
void *pixels; /**< Read-write */ |
||||
|
||||
/** Application data associated with the surface */ |
||||
void *userdata; /**< Read-write */ |
||||
|
||||
/** information needed for surfaces requiring locks */ |
||||
int locked; /**< Read-only */ |
||||
void *lock_data; /**< Read-only */ |
||||
|
||||
/** clipping information */ |
||||
SDL_Rect clip_rect; /**< Read-only */ |
||||
|
||||
/** info for fast blit mapping to other surfaces */ |
||||
struct SDL_BlitMap *map; /**< Private */ |
||||
|
||||
/** Reference count -- used when freeing surface */ |
||||
int refcount; /**< Read-mostly */ |
||||
} SDL_Surface; |
||||
|
||||
/**
|
||||
* \brief The type of function used for surface blitting functions. |
||||
*/ |
||||
typedef int (SDLCALL *SDL_blit) (struct SDL_Surface * src, SDL_Rect * srcrect, |
||||
struct SDL_Surface * dst, SDL_Rect * dstrect); |
||||
|
||||
/**
|
||||
* \brief The formula used for converting between YUV and RGB |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_YUV_CONVERSION_JPEG, /**< Full range JPEG */ |
||||
SDL_YUV_CONVERSION_BT601, /**< BT.601 (the default) */ |
||||
SDL_YUV_CONVERSION_BT709, /**< BT.709 */ |
||||
SDL_YUV_CONVERSION_AUTOMATIC /**< BT.601 for SD content, BT.709 for HD content */ |
||||
} SDL_YUV_CONVERSION_MODE; |
||||
|
||||
/**
|
||||
* Allocate and free an RGB surface. |
||||
* |
||||
* If the depth is 4 or 8 bits, an empty palette is allocated for the surface. |
||||
* If the depth is greater than 8 bits, the pixel format is set using the |
||||
* flags '[RGB]mask'. |
||||
* |
||||
* If the function runs out of memory, it will return NULL. |
||||
* |
||||
* \param flags The \c flags are obsolete and should be set to 0. |
||||
* \param width The width in pixels of the surface to create. |
||||
* \param height The height in pixels of the surface to create. |
||||
* \param depth The depth in bits of the surface to create. |
||||
* \param Rmask The red mask of the surface to create. |
||||
* \param Gmask The green mask of the surface to create. |
||||
* \param Bmask The blue mask of the surface to create. |
||||
* \param Amask The alpha mask of the surface to create. |
||||
*/ |
||||
extern DECLSPEC SDL_Surface *SDLCALL SDL_CreateRGBSurface |
||||
(Uint32 flags, int width, int height, int depth, |
||||
Uint32 Rmask, Uint32 Gmask, Uint32 Bmask, Uint32 Amask); |
||||
|
||||
/* !!! FIXME for 2.1: why does this ask for depth? Format provides that. */ |
||||
extern DECLSPEC SDL_Surface *SDLCALL SDL_CreateRGBSurfaceWithFormat |
||||
(Uint32 flags, int width, int height, int depth, Uint32 format); |
||||
|
||||
extern DECLSPEC SDL_Surface *SDLCALL SDL_CreateRGBSurfaceFrom(void *pixels, |
||||
int width, |
||||
int height, |
||||
int depth, |
||||
int pitch, |
||||
Uint32 Rmask, |
||||
Uint32 Gmask, |
||||
Uint32 Bmask, |
||||
Uint32 Amask); |
||||
extern DECLSPEC SDL_Surface *SDLCALL SDL_CreateRGBSurfaceWithFormatFrom |
||||
(void *pixels, int width, int height, int depth, int pitch, Uint32 format); |
||||
extern DECLSPEC void SDLCALL SDL_FreeSurface(SDL_Surface * surface); |
||||
|
||||
/**
|
||||
* \brief Set the palette used by a surface. |
||||
* |
||||
* \return 0, or -1 if the surface format doesn't use a palette. |
||||
* |
||||
* \note A single palette can be shared with many surfaces. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SetSurfacePalette(SDL_Surface * surface, |
||||
SDL_Palette * palette); |
||||
|
||||
/**
|
||||
* \brief Sets up a surface for directly accessing the pixels. |
||||
* |
||||
* Between calls to SDL_LockSurface() / SDL_UnlockSurface(), you can write |
||||
* to and read from \c surface->pixels, using the pixel format stored in |
||||
* \c surface->format. Once you are done accessing the surface, you should |
||||
* use SDL_UnlockSurface() to release it. |
||||
* |
||||
* Not all surfaces require locking. If SDL_MUSTLOCK(surface) evaluates |
||||
* to 0, then you can read and write to the surface at any time, and the |
||||
* pixel format of the surface will not change. |
||||
* |
||||
* No operating system or library calls should be made between lock/unlock |
||||
* pairs, as critical system locks may be held during this time. |
||||
* |
||||
* SDL_LockSurface() returns 0, or -1 if the surface couldn't be locked. |
||||
* |
||||
* \sa SDL_UnlockSurface() |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_LockSurface(SDL_Surface * surface); |
||||
/** \sa SDL_LockSurface() */ |
||||
extern DECLSPEC void SDLCALL SDL_UnlockSurface(SDL_Surface * surface); |
||||
|
||||
/**
|
||||
* Load a surface from a seekable SDL data stream (memory or file). |
||||
* |
||||
* If \c freesrc is non-zero, the stream will be closed after being read. |
||||
* |
||||
* The new surface should be freed with SDL_FreeSurface(). |
||||
* |
||||
* \return the new surface, or NULL if there was an error. |
||||
*/ |
||||
extern DECLSPEC SDL_Surface *SDLCALL SDL_LoadBMP_RW(SDL_RWops * src, |
||||
int freesrc); |
||||
|
||||
/**
|
||||
* Load a surface from a file. |
||||
* |
||||
* Convenience macro. |
||||
*/ |
||||
#define SDL_LoadBMP(file) SDL_LoadBMP_RW(SDL_RWFromFile(file, "rb"), 1) |
||||
|
||||
/**
|
||||
* Save a surface to a seekable SDL data stream (memory or file). |
||||
* |
||||
* Surfaces with a 24-bit, 32-bit and paletted 8-bit format get saved in the |
||||
* BMP directly. Other RGB formats with 8-bit or higher get converted to a |
||||
* 24-bit surface or, if they have an alpha mask or a colorkey, to a 32-bit |
||||
* surface before they are saved. YUV and paletted 1-bit and 4-bit formats are |
||||
* not supported. |
||||
* |
||||
* If \c freedst is non-zero, the stream will be closed after being written. |
||||
* |
||||
* \return 0 if successful or -1 if there was an error. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SaveBMP_RW |
||||
(SDL_Surface * surface, SDL_RWops * dst, int freedst); |
||||
|
||||
/**
|
||||
* Save a surface to a file. |
||||
* |
||||
* Convenience macro. |
||||
*/ |
||||
#define SDL_SaveBMP(surface, file) \ |
||||
SDL_SaveBMP_RW(surface, SDL_RWFromFile(file, "wb"), 1) |
||||
|
||||
/**
|
||||
* \brief Sets the RLE acceleration hint for a surface. |
||||
* |
||||
* \return 0 on success, or -1 if the surface is not valid |
||||
* |
||||
* \note If RLE is enabled, colorkey and alpha blending blits are much faster, |
||||
* but the surface must be locked before directly accessing the pixels. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SetSurfaceRLE(SDL_Surface * surface, |
||||
int flag); |
||||
|
||||
/**
|
||||
* \brief Sets the color key (transparent pixel) in a blittable surface. |
||||
* |
||||
* \param surface The surface to update |
||||
* \param flag Non-zero to enable colorkey and 0 to disable colorkey |
||||
* \param key The transparent pixel in the native surface format |
||||
* |
||||
* \return 0 on success, or -1 if the surface is not valid |
||||
* |
||||
* You can pass SDL_RLEACCEL to enable RLE accelerated blits. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SetColorKey(SDL_Surface * surface, |
||||
int flag, Uint32 key); |
||||
|
||||
/**
|
||||
* \brief Returns whether the surface has a color key |
||||
* |
||||
* \return SDL_TRUE if the surface has a color key, or SDL_FALSE if the surface is NULL or has no color key |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_HasColorKey(SDL_Surface * surface); |
||||
|
||||
/**
|
||||
* \brief Gets the color key (transparent pixel) in a blittable surface. |
||||
* |
||||
* \param surface The surface to update |
||||
* \param key A pointer filled in with the transparent pixel in the native |
||||
* surface format |
||||
* |
||||
* \return 0 on success, or -1 if the surface is not valid or colorkey is not |
||||
* enabled. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GetColorKey(SDL_Surface * surface, |
||||
Uint32 * key); |
||||
|
||||
/**
|
||||
* \brief Set an additional color value used in blit operations. |
||||
* |
||||
* \param surface The surface to update. |
||||
* \param r The red color value multiplied into blit operations. |
||||
* \param g The green color value multiplied into blit operations. |
||||
* \param b The blue color value multiplied into blit operations. |
||||
* |
||||
* \return 0 on success, or -1 if the surface is not valid. |
||||
* |
||||
* \sa SDL_GetSurfaceColorMod() |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SetSurfaceColorMod(SDL_Surface * surface, |
||||
Uint8 r, Uint8 g, Uint8 b); |
||||
|
||||
|
||||
/**
|
||||
* \brief Get the additional color value used in blit operations. |
||||
* |
||||
* \param surface The surface to query. |
||||
* \param r A pointer filled in with the current red color value. |
||||
* \param g A pointer filled in with the current green color value. |
||||
* \param b A pointer filled in with the current blue color value. |
||||
* |
||||
* \return 0 on success, or -1 if the surface is not valid. |
||||
* |
||||
* \sa SDL_SetSurfaceColorMod() |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GetSurfaceColorMod(SDL_Surface * surface, |
||||
Uint8 * r, Uint8 * g, |
||||
Uint8 * b); |
||||
|
||||
/**
|
||||
* \brief Set an additional alpha value used in blit operations. |
||||
* |
||||
* \param surface The surface to update. |
||||
* \param alpha The alpha value multiplied into blit operations. |
||||
* |
||||
* \return 0 on success, or -1 if the surface is not valid. |
||||
* |
||||
* \sa SDL_GetSurfaceAlphaMod() |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SetSurfaceAlphaMod(SDL_Surface * surface, |
||||
Uint8 alpha); |
||||
|
||||
/**
|
||||
* \brief Get the additional alpha value used in blit operations. |
||||
* |
||||
* \param surface The surface to query. |
||||
* \param alpha A pointer filled in with the current alpha value. |
||||
* |
||||
* \return 0 on success, or -1 if the surface is not valid. |
||||
* |
||||
* \sa SDL_SetSurfaceAlphaMod() |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GetSurfaceAlphaMod(SDL_Surface * surface, |
||||
Uint8 * alpha); |
||||
|
||||
/**
|
||||
* \brief Set the blend mode used for blit operations. |
||||
* |
||||
* \param surface The surface to update. |
||||
* \param blendMode ::SDL_BlendMode to use for blit blending. |
||||
* |
||||
* \return 0 on success, or -1 if the parameters are not valid. |
||||
* |
||||
* \sa SDL_GetSurfaceBlendMode() |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SetSurfaceBlendMode(SDL_Surface * surface, |
||||
SDL_BlendMode blendMode); |
||||
|
||||
/**
|
||||
* \brief Get the blend mode used for blit operations. |
||||
* |
||||
* \param surface The surface to query. |
||||
* \param blendMode A pointer filled in with the current blend mode. |
||||
* |
||||
* \return 0 on success, or -1 if the surface is not valid. |
||||
* |
||||
* \sa SDL_SetSurfaceBlendMode() |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_GetSurfaceBlendMode(SDL_Surface * surface, |
||||
SDL_BlendMode *blendMode); |
||||
|
||||
/**
|
||||
* Sets the clipping rectangle for the destination surface in a blit. |
||||
* |
||||
* If the clip rectangle is NULL, clipping will be disabled. |
||||
* |
||||
* If the clip rectangle doesn't intersect the surface, the function will |
||||
* return SDL_FALSE and blits will be completely clipped. Otherwise the |
||||
* function returns SDL_TRUE and blits to the surface will be clipped to |
||||
* the intersection of the surface area and the clipping rectangle. |
||||
* |
||||
* Note that blits are automatically clipped to the edges of the source |
||||
* and destination surfaces. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_SetClipRect(SDL_Surface * surface, |
||||
const SDL_Rect * rect); |
||||
|
||||
/**
|
||||
* Gets the clipping rectangle for the destination surface in a blit. |
||||
* |
||||
* \c rect must be a pointer to a valid rectangle which will be filled |
||||
* with the correct values. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_GetClipRect(SDL_Surface * surface, |
||||
SDL_Rect * rect); |
||||
|
||||
/*
|
||||
* Creates a new surface identical to the existing surface |
||||
*/ |
||||
extern DECLSPEC SDL_Surface *SDLCALL SDL_DuplicateSurface(SDL_Surface * surface); |
||||
|
||||
/**
|
||||
* Creates a new surface of the specified format, and then copies and maps |
||||
* the given surface to it so the blit of the converted surface will be as |
||||
* fast as possible. If this function fails, it returns NULL. |
||||
* |
||||
* The \c flags parameter is passed to SDL_CreateRGBSurface() and has those |
||||
* semantics. You can also pass ::SDL_RLEACCEL in the flags parameter and |
||||
* SDL will try to RLE accelerate colorkey and alpha blits in the resulting |
||||
* surface. |
||||
*/ |
||||
extern DECLSPEC SDL_Surface *SDLCALL SDL_ConvertSurface |
||||
(SDL_Surface * src, const SDL_PixelFormat * fmt, Uint32 flags); |
||||
extern DECLSPEC SDL_Surface *SDLCALL SDL_ConvertSurfaceFormat |
||||
(SDL_Surface * src, Uint32 pixel_format, Uint32 flags); |
||||
|
||||
/**
|
||||
* \brief Copy a block of pixels of one format to another format |
||||
* |
||||
* \return 0 on success, or -1 if there was an error |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_ConvertPixels(int width, int height, |
||||
Uint32 src_format, |
||||
const void * src, int src_pitch, |
||||
Uint32 dst_format, |
||||
void * dst, int dst_pitch); |
||||
|
||||
/**
|
||||
* Performs a fast fill of the given rectangle with \c color. |
||||
* |
||||
* If \c rect is NULL, the whole surface will be filled with \c color. |
||||
* |
||||
* The color should be a pixel of the format used by the surface, and |
||||
* can be generated by the SDL_MapRGB() function. |
||||
* |
||||
* \return 0 on success, or -1 on error. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_FillRect |
||||
(SDL_Surface * dst, const SDL_Rect * rect, Uint32 color); |
||||
extern DECLSPEC int SDLCALL SDL_FillRects |
||||
(SDL_Surface * dst, const SDL_Rect * rects, int count, Uint32 color); |
||||
|
||||
/**
|
||||
* Performs a fast blit from the source surface to the destination surface. |
||||
* |
||||
* This assumes that the source and destination rectangles are |
||||
* the same size. If either \c srcrect or \c dstrect are NULL, the entire |
||||
* surface (\c src or \c dst) is copied. The final blit rectangles are saved |
||||
* in \c srcrect and \c dstrect after all clipping is performed. |
||||
* |
||||
* \return If the blit is successful, it returns 0, otherwise it returns -1. |
||||
* |
||||
* The blit function should not be called on a locked surface. |
||||
* |
||||
* The blit semantics for surfaces with and without blending and colorkey |
||||
* are defined as follows: |
||||
* \verbatim |
||||
RGBA->RGB: |
||||
Source surface blend mode set to SDL_BLENDMODE_BLEND: |
||||
alpha-blend (using the source alpha-channel and per-surface alpha) |
||||
SDL_SRCCOLORKEY ignored. |
||||
Source surface blend mode set to SDL_BLENDMODE_NONE: |
||||
copy RGB. |
||||
if SDL_SRCCOLORKEY set, only copy the pixels matching the |
||||
RGB values of the source color key, ignoring alpha in the |
||||
comparison. |
||||
|
||||
RGB->RGBA: |
||||
Source surface blend mode set to SDL_BLENDMODE_BLEND: |
||||
alpha-blend (using the source per-surface alpha) |
||||
Source surface blend mode set to SDL_BLENDMODE_NONE: |
||||
copy RGB, set destination alpha to source per-surface alpha value. |
||||
both: |
||||
if SDL_SRCCOLORKEY set, only copy the pixels matching the |
||||
source color key. |
||||
|
||||
RGBA->RGBA: |
||||
Source surface blend mode set to SDL_BLENDMODE_BLEND: |
||||
alpha-blend (using the source alpha-channel and per-surface alpha) |
||||
SDL_SRCCOLORKEY ignored. |
||||
Source surface blend mode set to SDL_BLENDMODE_NONE: |
||||
copy all of RGBA to the destination. |
||||
if SDL_SRCCOLORKEY set, only copy the pixels matching the |
||||
RGB values of the source color key, ignoring alpha in the |
||||
comparison. |
||||
|
||||
RGB->RGB: |
||||
Source surface blend mode set to SDL_BLENDMODE_BLEND: |
||||
alpha-blend (using the source per-surface alpha) |
||||
Source surface blend mode set to SDL_BLENDMODE_NONE: |
||||
copy RGB. |
||||
both: |
||||
if SDL_SRCCOLORKEY set, only copy the pixels matching the |
||||
source color key. |
||||
\endverbatim |
||||
* |
||||
* You should call SDL_BlitSurface() unless you know exactly how SDL |
||||
* blitting works internally and how to use the other blit functions. |
||||
*/ |
||||
#define SDL_BlitSurface SDL_UpperBlit |
||||
|
||||
/**
|
||||
* This is the public blit function, SDL_BlitSurface(), and it performs |
||||
* rectangle validation and clipping before passing it to SDL_LowerBlit() |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_UpperBlit |
||||
(SDL_Surface * src, const SDL_Rect * srcrect, |
||||
SDL_Surface * dst, SDL_Rect * dstrect); |
||||
|
||||
/**
|
||||
* This is a semi-private blit function and it performs low-level surface |
||||
* blitting only. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_LowerBlit |
||||
(SDL_Surface * src, SDL_Rect * srcrect, |
||||
SDL_Surface * dst, SDL_Rect * dstrect); |
||||
|
||||
/**
|
||||
* \brief Perform a fast, low quality, stretch blit between two surfaces of the |
||||
* same pixel format. |
||||
* |
||||
* \note This function uses a static buffer, and is not thread-safe. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_SoftStretch(SDL_Surface * src, |
||||
const SDL_Rect * srcrect, |
||||
SDL_Surface * dst, |
||||
const SDL_Rect * dstrect); |
||||
|
||||
#define SDL_BlitScaled SDL_UpperBlitScaled |
||||
|
||||
/**
|
||||
* This is the public scaled blit function, SDL_BlitScaled(), and it performs |
||||
* rectangle validation and clipping before passing it to SDL_LowerBlitScaled() |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_UpperBlitScaled |
||||
(SDL_Surface * src, const SDL_Rect * srcrect, |
||||
SDL_Surface * dst, SDL_Rect * dstrect); |
||||
|
||||
/**
|
||||
* This is a semi-private blit function and it performs low-level surface |
||||
* scaled blitting only. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_LowerBlitScaled |
||||
(SDL_Surface * src, SDL_Rect * srcrect, |
||||
SDL_Surface * dst, SDL_Rect * dstrect); |
||||
|
||||
/**
|
||||
* \brief Set the YUV conversion mode |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_SetYUVConversionMode(SDL_YUV_CONVERSION_MODE mode); |
||||
|
||||
/**
|
||||
* \brief Get the YUV conversion mode |
||||
*/ |
||||
extern DECLSPEC SDL_YUV_CONVERSION_MODE SDLCALL SDL_GetYUVConversionMode(void); |
||||
|
||||
/**
|
||||
* \brief Get the YUV conversion mode, returning the correct mode for the resolution when the current conversion mode is SDL_YUV_CONVERSION_AUTOMATIC |
||||
*/ |
||||
extern DECLSPEC SDL_YUV_CONVERSION_MODE SDLCALL SDL_GetYUVConversionModeForResolution(int width, int height); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_surface_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,279 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_system.h |
||||
* |
||||
* Include file for platform specific SDL API functions |
||||
*/ |
||||
|
||||
#ifndef SDL_system_h_ |
||||
#define SDL_system_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_keyboard.h" |
||||
#include "SDL_render.h" |
||||
#include "SDL_video.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
/* Platform specific functions for Windows */ |
||||
#ifdef __WIN32__ |
||||
|
||||
/**
|
||||
\brief Set a function that is called for every windows message, before TranslateMessage() |
||||
*/ |
||||
typedef void (SDLCALL * SDL_WindowsMessageHook)(void *userdata, void *hWnd, unsigned int message, Uint64 wParam, Sint64 lParam); |
||||
extern DECLSPEC void SDLCALL SDL_SetWindowsMessageHook(SDL_WindowsMessageHook callback, void *userdata); |
||||
|
||||
/**
|
||||
\brief Returns the D3D9 adapter index that matches the specified display index. |
||||
|
||||
This adapter index can be passed to IDirect3D9::CreateDevice and controls |
||||
on which monitor a full screen application will appear. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_Direct3D9GetAdapterIndex( int displayIndex ); |
||||
|
||||
typedef struct IDirect3DDevice9 IDirect3DDevice9; |
||||
/**
|
||||
\brief Returns the D3D device associated with a renderer, or NULL if it's not a D3D renderer. |
||||
|
||||
Once you are done using the device, you should release it to avoid a resource leak. |
||||
*/ |
||||
extern DECLSPEC IDirect3DDevice9* SDLCALL SDL_RenderGetD3D9Device(SDL_Renderer * renderer); |
||||
|
||||
/**
|
||||
\brief Returns the DXGI Adapter and Output indices for the specified display index. |
||||
|
||||
These can be passed to EnumAdapters and EnumOutputs respectively to get the objects |
||||
required to create a DX10 or DX11 device and swap chain. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_DXGIGetOutputInfo( int displayIndex, int *adapterIndex, int *outputIndex ); |
||||
|
||||
#endif /* __WIN32__ */ |
||||
|
||||
|
||||
/* Platform specific functions for Linux */ |
||||
#ifdef __LINUX__ |
||||
|
||||
/**
|
||||
\brief Sets the UNIX nice value for a thread, using setpriority() if possible, and RealtimeKit if available. |
||||
|
||||
\return 0 on success, or -1 on error. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_LinuxSetThreadPriority(Sint64 threadID, int priority); |
||||
|
||||
#endif /* __LINUX__ */ |
||||
|
||||
/* Platform specific functions for iOS */ |
||||
#if defined(__IPHONEOS__) && __IPHONEOS__ |
||||
|
||||
#define SDL_iOSSetAnimationCallback(window, interval, callback, callbackParam) SDL_iPhoneSetAnimationCallback(window, interval, callback, callbackParam) |
||||
extern DECLSPEC int SDLCALL SDL_iPhoneSetAnimationCallback(SDL_Window * window, int interval, void (*callback)(void*), void *callbackParam); |
||||
|
||||
#define SDL_iOSSetEventPump(enabled) SDL_iPhoneSetEventPump(enabled) |
||||
extern DECLSPEC void SDLCALL SDL_iPhoneSetEventPump(SDL_bool enabled); |
||||
|
||||
#endif /* __IPHONEOS__ */ |
||||
|
||||
|
||||
/* Platform specific functions for Android */ |
||||
#if defined(__ANDROID__) && __ANDROID__ |
||||
|
||||
/**
|
||||
\brief Get the JNI environment for the current thread |
||||
|
||||
This returns JNIEnv*, but the prototype is void* so we don't need jni.h |
||||
*/ |
||||
extern DECLSPEC void * SDLCALL SDL_AndroidGetJNIEnv(void); |
||||
|
||||
/**
|
||||
\brief Get the SDL Activity object for the application |
||||
|
||||
This returns jobject, but the prototype is void* so we don't need jni.h |
||||
The jobject returned by SDL_AndroidGetActivity is a local reference. |
||||
It is the caller's responsibility to properly release it |
||||
(using env->Push/PopLocalFrame or manually with env->DeleteLocalRef) |
||||
*/ |
||||
extern DECLSPEC void * SDLCALL SDL_AndroidGetActivity(void); |
||||
|
||||
/**
|
||||
\brief Return true if the application is running on Android TV |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_IsAndroidTV(void); |
||||
|
||||
/**
|
||||
\brief Return true if the application is running on a Chromebook |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_IsChromebook(void); |
||||
|
||||
/**
|
||||
\brief Return true is the application is running on a Samsung DeX docking station |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_IsDeXMode(void); |
||||
|
||||
/**
|
||||
\brief Trigger the Android system back button behavior. |
||||
*/ |
||||
extern DECLSPEC void SDLCALL SDL_AndroidBackButton(void); |
||||
|
||||
/**
|
||||
See the official Android developer guide for more information: |
||||
http://developer.android.com/guide/topics/data/data-storage.html
|
||||
*/ |
||||
#define SDL_ANDROID_EXTERNAL_STORAGE_READ 0x01 |
||||
#define SDL_ANDROID_EXTERNAL_STORAGE_WRITE 0x02 |
||||
|
||||
/**
|
||||
\brief Get the path used for internal storage for this application. |
||||
|
||||
This path is unique to your application and cannot be written to |
||||
by other applications. |
||||
*/ |
||||
extern DECLSPEC const char * SDLCALL SDL_AndroidGetInternalStoragePath(void); |
||||
|
||||
/**
|
||||
\brief Get the current state of external storage, a bitmask of these values: |
||||
SDL_ANDROID_EXTERNAL_STORAGE_READ |
||||
SDL_ANDROID_EXTERNAL_STORAGE_WRITE |
||||
|
||||
If external storage is currently unavailable, this will return 0. |
||||
*/ |
||||
extern DECLSPEC int SDLCALL SDL_AndroidGetExternalStorageState(void); |
||||
|
||||
/**
|
||||
\brief Get the path used for external storage for this application. |
||||
|
||||
This path is unique to your application, but is public and can be |
||||
written to by other applications. |
||||
*/ |
||||
extern DECLSPEC const char * SDLCALL SDL_AndroidGetExternalStoragePath(void); |
||||
|
||||
#endif /* __ANDROID__ */ |
||||
|
||||
/* Platform specific functions for WinRT */ |
||||
#if defined(__WINRT__) && __WINRT__ |
||||
|
||||
/**
|
||||
* \brief WinRT / Windows Phone path types |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
/** \brief The installed app's root directory.
|
||||
Files here are likely to be read-only. */ |
||||
SDL_WINRT_PATH_INSTALLED_LOCATION, |
||||
|
||||
/** \brief The app's local data store. Files may be written here */ |
||||
SDL_WINRT_PATH_LOCAL_FOLDER, |
||||
|
||||
/** \brief The app's roaming data store. Unsupported on Windows Phone.
|
||||
Files written here may be copied to other machines via a network |
||||
connection. |
||||
*/ |
||||
SDL_WINRT_PATH_ROAMING_FOLDER, |
||||
|
||||
/** \brief The app's temporary data store. Unsupported on Windows Phone.
|
||||
Files written here may be deleted at any time. */ |
||||
SDL_WINRT_PATH_TEMP_FOLDER |
||||
} SDL_WinRT_Path; |
||||
|
||||
|
||||
/**
|
||||
* \brief WinRT Device Family |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
/** \brief Unknown family */ |
||||
SDL_WINRT_DEVICEFAMILY_UNKNOWN, |
||||
|
||||
/** \brief Desktop family*/ |
||||
SDL_WINRT_DEVICEFAMILY_DESKTOP, |
||||
|
||||
/** \brief Mobile family (for example smartphone) */ |
||||
SDL_WINRT_DEVICEFAMILY_MOBILE, |
||||
|
||||
/** \brief XBox family */ |
||||
SDL_WINRT_DEVICEFAMILY_XBOX, |
||||
} SDL_WinRT_DeviceFamily; |
||||
|
||||
|
||||
/**
|
||||
* \brief Retrieves a WinRT defined path on the local file system |
||||
* |
||||
* \note Documentation on most app-specific path types on WinRT |
||||
* can be found on MSDN, at the URL: |
||||
* http://msdn.microsoft.com/en-us/library/windows/apps/hh464917.aspx
|
||||
* |
||||
* \param pathType The type of path to retrieve. |
||||
* \return A UCS-2 string (16-bit, wide-char) containing the path, or NULL |
||||
* if the path is not available for any reason. Not all paths are |
||||
* available on all versions of Windows. This is especially true on |
||||
* Windows Phone. Check the documentation for the given |
||||
* SDL_WinRT_Path for more information on which path types are |
||||
* supported where. |
||||
*/ |
||||
extern DECLSPEC const wchar_t * SDLCALL SDL_WinRTGetFSPathUNICODE(SDL_WinRT_Path pathType); |
||||
|
||||
/**
|
||||
* \brief Retrieves a WinRT defined path on the local file system |
||||
* |
||||
* \note Documentation on most app-specific path types on WinRT |
||||
* can be found on MSDN, at the URL: |
||||
* http://msdn.microsoft.com/en-us/library/windows/apps/hh464917.aspx
|
||||
* |
||||
* \param pathType The type of path to retrieve. |
||||
* \return A UTF-8 string (8-bit, multi-byte) containing the path, or NULL |
||||
* if the path is not available for any reason. Not all paths are |
||||
* available on all versions of Windows. This is especially true on |
||||
* Windows Phone. Check the documentation for the given |
||||
* SDL_WinRT_Path for more information on which path types are |
||||
* supported where. |
||||
*/ |
||||
extern DECLSPEC const char * SDLCALL SDL_WinRTGetFSPathUTF8(SDL_WinRT_Path pathType); |
||||
|
||||
/**
|
||||
* \brief Detects the device family of WinRT plattform on runtime |
||||
* |
||||
* \return Device family |
||||
*/ |
||||
extern DECLSPEC SDL_WinRT_DeviceFamily SDLCALL SDL_WinRTGetDeviceFamily(); |
||||
|
||||
#endif /* __WINRT__ */ |
||||
|
||||
/**
|
||||
\brief Return true if the current device is a tablet. |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_IsTablet(void); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_system_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,327 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_syswm.h |
||||
* |
||||
* Include file for SDL custom system window manager hooks. |
||||
*/ |
||||
|
||||
#ifndef SDL_syswm_h_ |
||||
#define SDL_syswm_h_ |
||||
|
||||
#include "SDL_stdinc.h" |
||||
#include "SDL_error.h" |
||||
#include "SDL_video.h" |
||||
#include "SDL_version.h" |
||||
|
||||
/**
|
||||
* \brief SDL_syswm.h |
||||
* |
||||
* Your application has access to a special type of event ::SDL_SYSWMEVENT, |
||||
* which contains window-manager specific information and arrives whenever |
||||
* an unhandled window event occurs. This event is ignored by default, but |
||||
* you can enable it with SDL_EventState(). |
||||
*/ |
||||
struct SDL_SysWMinfo; |
||||
|
||||
#if !defined(SDL_PROTOTYPES_ONLY) |
||||
|
||||
#if defined(SDL_VIDEO_DRIVER_WINDOWS) |
||||
#ifndef WIN32_LEAN_AND_MEAN |
||||
#define WIN32_LEAN_AND_MEAN |
||||
#endif |
||||
#include <windows.h> |
||||
#endif |
||||
|
||||
#if defined(SDL_VIDEO_DRIVER_WINRT) |
||||
#include <Inspectable.h> |
||||
#endif |
||||
|
||||
/* This is the structure for custom window manager events */ |
||||
#if defined(SDL_VIDEO_DRIVER_X11) |
||||
#if defined(__APPLE__) && defined(__MACH__) |
||||
/* conflicts with Quickdraw.h */ |
||||
#define Cursor X11Cursor |
||||
#endif |
||||
|
||||
#include <X11/Xlib.h> |
||||
#include <X11/Xatom.h> |
||||
|
||||
#if defined(__APPLE__) && defined(__MACH__) |
||||
/* matches the re-define above */ |
||||
#undef Cursor |
||||
#endif |
||||
|
||||
#endif /* defined(SDL_VIDEO_DRIVER_X11) */ |
||||
|
||||
#if defined(SDL_VIDEO_DRIVER_DIRECTFB) |
||||
#include <directfb.h> |
||||
#endif |
||||
|
||||
#if defined(SDL_VIDEO_DRIVER_COCOA) |
||||
#ifdef __OBJC__ |
||||
@class NSWindow; |
||||
#else |
||||
typedef struct _NSWindow NSWindow; |
||||
#endif |
||||
#endif |
||||
|
||||
#if defined(SDL_VIDEO_DRIVER_UIKIT) |
||||
#ifdef __OBJC__ |
||||
#include <UIKit/UIKit.h> |
||||
#else |
||||
typedef struct _UIWindow UIWindow; |
||||
typedef struct _UIViewController UIViewController; |
||||
#endif |
||||
typedef Uint32 GLuint; |
||||
#endif |
||||
|
||||
#if defined(SDL_VIDEO_DRIVER_ANDROID) |
||||
typedef struct ANativeWindow ANativeWindow; |
||||
typedef void *EGLSurface; |
||||
#endif |
||||
|
||||
#if defined(SDL_VIDEO_DRIVER_VIVANTE) |
||||
#include "SDL_egl.h" |
||||
#endif |
||||
#endif /* SDL_PROTOTYPES_ONLY */ |
||||
|
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
#if !defined(SDL_PROTOTYPES_ONLY) |
||||
/**
|
||||
* These are the various supported windowing subsystems |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
SDL_SYSWM_UNKNOWN, |
||||
SDL_SYSWM_WINDOWS, |
||||
SDL_SYSWM_X11, |
||||
SDL_SYSWM_DIRECTFB, |
||||
SDL_SYSWM_COCOA, |
||||
SDL_SYSWM_UIKIT, |
||||
SDL_SYSWM_WAYLAND, |
||||
SDL_SYSWM_MIR, /* no longer available, left for API/ABI compatibility. Remove in 2.1! */ |
||||
SDL_SYSWM_WINRT, |
||||
SDL_SYSWM_ANDROID, |
||||
SDL_SYSWM_VIVANTE, |
||||
SDL_SYSWM_OS2 |
||||
} SDL_SYSWM_TYPE; |
||||
|
||||
/**
|
||||
* The custom event structure. |
||||
*/ |
||||
struct SDL_SysWMmsg |
||||
{ |
||||
SDL_version version; |
||||
SDL_SYSWM_TYPE subsystem; |
||||
union |
||||
{ |
||||
#if defined(SDL_VIDEO_DRIVER_WINDOWS) |
||||
struct { |
||||
HWND hwnd; /**< The window for the message */ |
||||
UINT msg; /**< The type of message */ |
||||
WPARAM wParam; /**< WORD message parameter */ |
||||
LPARAM lParam; /**< LONG message parameter */ |
||||
} win; |
||||
#endif |
||||
#if defined(SDL_VIDEO_DRIVER_X11) |
||||
struct { |
||||
XEvent event; |
||||
} x11; |
||||
#endif |
||||
#if defined(SDL_VIDEO_DRIVER_DIRECTFB) |
||||
struct { |
||||
DFBEvent event; |
||||
} dfb; |
||||
#endif |
||||
#if defined(SDL_VIDEO_DRIVER_COCOA) |
||||
struct |
||||
{ |
||||
/* Latest version of Xcode clang complains about empty structs in C v. C++:
|
||||
error: empty struct has size 0 in C, size 1 in C++ |
||||
*/ |
||||
int dummy; |
||||
/* No Cocoa window events yet */ |
||||
} cocoa; |
||||
#endif |
||||
#if defined(SDL_VIDEO_DRIVER_UIKIT) |
||||
struct |
||||
{ |
||||
int dummy; |
||||
/* No UIKit window events yet */ |
||||
} uikit; |
||||
#endif |
||||
#if defined(SDL_VIDEO_DRIVER_VIVANTE) |
||||
struct |
||||
{ |
||||
int dummy; |
||||
/* No Vivante window events yet */ |
||||
} vivante; |
||||
#endif |
||||
/* Can't have an empty union */ |
||||
int dummy; |
||||
} msg; |
||||
}; |
||||
|
||||
/**
|
||||
* The custom window manager information structure. |
||||
* |
||||
* When this structure is returned, it holds information about which |
||||
* low level system it is using, and will be one of SDL_SYSWM_TYPE. |
||||
*/ |
||||
struct SDL_SysWMinfo |
||||
{ |
||||
SDL_version version; |
||||
SDL_SYSWM_TYPE subsystem; |
||||
union |
||||
{ |
||||
#if defined(SDL_VIDEO_DRIVER_WINDOWS) |
||||
struct |
||||
{ |
||||
HWND window; /**< The window handle */ |
||||
HDC hdc; /**< The window device context */ |
||||
HINSTANCE hinstance; /**< The instance handle */ |
||||
} win; |
||||
#endif |
||||
#if defined(SDL_VIDEO_DRIVER_WINRT) |
||||
struct |
||||
{ |
||||
IInspectable * window; /**< The WinRT CoreWindow */ |
||||
} winrt; |
||||
#endif |
||||
#if defined(SDL_VIDEO_DRIVER_X11) |
||||
struct |
||||
{ |
||||
Display *display; /**< The X11 display */ |
||||
Window window; /**< The X11 window */ |
||||
} x11; |
||||
#endif |
||||
#if defined(SDL_VIDEO_DRIVER_DIRECTFB) |
||||
struct |
||||
{ |
||||
IDirectFB *dfb; /**< The directfb main interface */ |
||||
IDirectFBWindow *window; /**< The directfb window handle */ |
||||
IDirectFBSurface *surface; /**< The directfb client surface */ |
||||
} dfb; |
||||
#endif |
||||
#if defined(SDL_VIDEO_DRIVER_COCOA) |
||||
struct |
||||
{ |
||||
#if defined(__OBJC__) && defined(__has_feature) && __has_feature(objc_arc) |
||||
NSWindow __unsafe_unretained *window; /**< The Cocoa window */ |
||||
#else |
||||
NSWindow *window; /**< The Cocoa window */ |
||||
#endif |
||||
} cocoa; |
||||
#endif |
||||
#if defined(SDL_VIDEO_DRIVER_UIKIT) |
||||
struct |
||||
{ |
||||
#if defined(__OBJC__) && defined(__has_feature) && __has_feature(objc_arc) |
||||
UIWindow __unsafe_unretained *window; /**< The UIKit window */ |
||||
#else |
||||
UIWindow *window; /**< The UIKit window */ |
||||
#endif |
||||
GLuint framebuffer; /**< The GL view's Framebuffer Object. It must be bound when rendering to the screen using GL. */ |
||||
GLuint colorbuffer; /**< The GL view's color Renderbuffer Object. It must be bound when SDL_GL_SwapWindow is called. */ |
||||
GLuint resolveFramebuffer; /**< The Framebuffer Object which holds the resolve color Renderbuffer, when MSAA is used. */ |
||||
} uikit; |
||||
#endif |
||||
#if defined(SDL_VIDEO_DRIVER_WAYLAND) |
||||
struct |
||||
{ |
||||
struct wl_display *display; /**< Wayland display */ |
||||
struct wl_surface *surface; /**< Wayland surface */ |
||||
struct wl_shell_surface *shell_surface; /**< Wayland shell_surface (window manager handle) */ |
||||
} wl; |
||||
#endif |
||||
#if defined(SDL_VIDEO_DRIVER_MIR) /* no longer available, left for API/ABI compatibility. Remove in 2.1! */ |
||||
struct |
||||
{ |
||||
void *connection; /**< Mir display server connection */ |
||||
void *surface; /**< Mir surface */ |
||||
} mir; |
||||
#endif |
||||
|
||||
#if defined(SDL_VIDEO_DRIVER_ANDROID) |
||||
struct |
||||
{ |
||||
ANativeWindow *window; |
||||
EGLSurface surface; |
||||
} android; |
||||
#endif |
||||
|
||||
#if defined(SDL_VIDEO_DRIVER_VIVANTE) |
||||
struct |
||||
{ |
||||
EGLNativeDisplayType display; |
||||
EGLNativeWindowType window; |
||||
} vivante; |
||||
#endif |
||||
|
||||
/* Make sure this union is always 64 bytes (8 64-bit pointers). */ |
||||
/* Be careful not to overflow this if you add a new target! */ |
||||
Uint8 dummy[64]; |
||||
} info; |
||||
}; |
||||
|
||||
#endif /* SDL_PROTOTYPES_ONLY */ |
||||
|
||||
typedef struct SDL_SysWMinfo SDL_SysWMinfo; |
||||
|
||||
/* Function prototypes */ |
||||
/**
|
||||
* \brief This function allows access to driver-dependent window information. |
||||
* |
||||
* \param window The window about which information is being requested |
||||
* \param info This structure must be initialized with the SDL version, and is |
||||
* then filled in with information about the given window. |
||||
* |
||||
* \return SDL_TRUE if the function is implemented and the version member of |
||||
* the \c info struct is valid, SDL_FALSE otherwise. |
||||
* |
||||
* You typically use this function like this: |
||||
* \code |
||||
* SDL_SysWMinfo info; |
||||
* SDL_VERSION(&info.version); |
||||
* if ( SDL_GetWindowWMInfo(window, &info) ) { ... } |
||||
* \endcode |
||||
*/ |
||||
extern DECLSPEC SDL_bool SDLCALL SDL_GetWindowWMInfo(SDL_Window * window, |
||||
SDL_SysWMinfo * info); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_syswm_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,69 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
#ifndef SDL_test_h_ |
||||
#define SDL_test_h_ |
||||
|
||||
#include "SDL.h" |
||||
#include "SDL_test_assert.h" |
||||
#include "SDL_test_common.h" |
||||
#include "SDL_test_compare.h" |
||||
#include "SDL_test_crc32.h" |
||||
#include "SDL_test_font.h" |
||||
#include "SDL_test_fuzzer.h" |
||||
#include "SDL_test_harness.h" |
||||
#include "SDL_test_images.h" |
||||
#include "SDL_test_log.h" |
||||
#include "SDL_test_md5.h" |
||||
#include "SDL_test_memory.h" |
||||
#include "SDL_test_random.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* Global definitions */ |
||||
|
||||
/*
|
||||
* Note: Maximum size of SDLTest log message is less than SDL's limit |
||||
* to ensure we can fit additional information such as the timestamp. |
||||
*/ |
||||
#define SDLTEST_MAX_LOGMESSAGE_LENGTH 3584 |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,105 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test_assert.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
/*
|
||||
* |
||||
* Assert API for test code and test cases |
||||
* |
||||
*/ |
||||
|
||||
#ifndef SDL_test_assert_h_ |
||||
#define SDL_test_assert_h_ |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief Fails the assert. |
||||
*/ |
||||
#define ASSERT_FAIL 0 |
||||
|
||||
/**
|
||||
* \brief Passes the assert. |
||||
*/ |
||||
#define ASSERT_PASS 1 |
||||
|
||||
/**
|
||||
* \brief Assert that logs and break execution flow on failures. |
||||
* |
||||
* \param assertCondition Evaluated condition or variable to assert; fail (==0) or pass (!=0). |
||||
* \param assertDescription Message to log with the assert describing it. |
||||
*/ |
||||
void SDLTest_Assert(int assertCondition, SDL_PRINTF_FORMAT_STRING const char *assertDescription, ...) SDL_PRINTF_VARARG_FUNC(2); |
||||
|
||||
/**
|
||||
* \brief Assert for test cases that logs but does not break execution flow on failures. Updates assertion counters. |
||||
* |
||||
* \param assertCondition Evaluated condition or variable to assert; fail (==0) or pass (!=0). |
||||
* \param assertDescription Message to log with the assert describing it. |
||||
* |
||||
* \returns Returns the assertCondition so it can be used to externally to break execution flow if desired. |
||||
*/ |
||||
int SDLTest_AssertCheck(int assertCondition, SDL_PRINTF_FORMAT_STRING const char *assertDescription, ...) SDL_PRINTF_VARARG_FUNC(2); |
||||
|
||||
/**
|
||||
* \brief Explicitly pass without checking an assertion condition. Updates assertion counter. |
||||
* |
||||
* \param assertDescription Message to log with the assert describing it. |
||||
*/ |
||||
void SDLTest_AssertPass(SDL_PRINTF_FORMAT_STRING const char *assertDescription, ...) SDL_PRINTF_VARARG_FUNC(1); |
||||
|
||||
/**
|
||||
* \brief Resets the assert summary counters to zero. |
||||
*/ |
||||
void SDLTest_ResetAssertSummary(void); |
||||
|
||||
/**
|
||||
* \brief Logs summary of all assertions (total, pass, fail) since last reset as INFO or ERROR. |
||||
*/ |
||||
void SDLTest_LogAssertSummary(void); |
||||
|
||||
|
||||
/**
|
||||
* \brief Converts the current assert summary state to a test result. |
||||
* |
||||
* \returns TEST_RESULT_PASSED, TEST_RESULT_FAILED, or TEST_RESULT_NO_ASSERT |
||||
*/ |
||||
int SDLTest_AssertSummaryToTestResult(void); |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_assert_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,205 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test_common.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
/* Ported from original test\common.h file. */ |
||||
|
||||
#ifndef SDL_test_common_h_ |
||||
#define SDL_test_common_h_ |
||||
|
||||
#include "SDL.h" |
||||
|
||||
#if defined(__PSP__) |
||||
#define DEFAULT_WINDOW_WIDTH 480 |
||||
#define DEFAULT_WINDOW_HEIGHT 272 |
||||
#else |
||||
#define DEFAULT_WINDOW_WIDTH 640 |
||||
#define DEFAULT_WINDOW_HEIGHT 480 |
||||
#endif |
||||
|
||||
#define VERBOSE_VIDEO 0x00000001 |
||||
#define VERBOSE_MODES 0x00000002 |
||||
#define VERBOSE_RENDER 0x00000004 |
||||
#define VERBOSE_EVENT 0x00000008 |
||||
#define VERBOSE_AUDIO 0x00000010 |
||||
|
||||
typedef struct |
||||
{ |
||||
/* SDL init flags */ |
||||
char **argv; |
||||
Uint32 flags; |
||||
Uint32 verbose; |
||||
|
||||
/* Video info */ |
||||
const char *videodriver; |
||||
int display; |
||||
const char *window_title; |
||||
const char *window_icon; |
||||
Uint32 window_flags; |
||||
int window_x; |
||||
int window_y; |
||||
int window_w; |
||||
int window_h; |
||||
int window_minW; |
||||
int window_minH; |
||||
int window_maxW; |
||||
int window_maxH; |
||||
int logical_w; |
||||
int logical_h; |
||||
float scale; |
||||
int depth; |
||||
int refresh_rate; |
||||
int num_windows; |
||||
SDL_Window **windows; |
||||
|
||||
/* Renderer info */ |
||||
const char *renderdriver; |
||||
Uint32 render_flags; |
||||
SDL_bool skip_renderer; |
||||
SDL_Renderer **renderers; |
||||
SDL_Texture **targets; |
||||
|
||||
/* Audio info */ |
||||
const char *audiodriver; |
||||
SDL_AudioSpec audiospec; |
||||
|
||||
/* GL settings */ |
||||
int gl_red_size; |
||||
int gl_green_size; |
||||
int gl_blue_size; |
||||
int gl_alpha_size; |
||||
int gl_buffer_size; |
||||
int gl_depth_size; |
||||
int gl_stencil_size; |
||||
int gl_double_buffer; |
||||
int gl_accum_red_size; |
||||
int gl_accum_green_size; |
||||
int gl_accum_blue_size; |
||||
int gl_accum_alpha_size; |
||||
int gl_stereo; |
||||
int gl_multisamplebuffers; |
||||
int gl_multisamplesamples; |
||||
int gl_retained_backing; |
||||
int gl_accelerated; |
||||
int gl_major_version; |
||||
int gl_minor_version; |
||||
int gl_debug; |
||||
int gl_profile_mask; |
||||
} SDLTest_CommonState; |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* Function prototypes */ |
||||
|
||||
/**
|
||||
* \brief Parse command line parameters and create common state. |
||||
* |
||||
* \param argv Array of command line parameters |
||||
* \param flags Flags indicating which subsystem to initialize (i.e. SDL_INIT_VIDEO | SDL_INIT_AUDIO) |
||||
* |
||||
* \returns Returns a newly allocated common state object. |
||||
*/ |
||||
SDLTest_CommonState *SDLTest_CommonCreateState(char **argv, Uint32 flags); |
||||
|
||||
/**
|
||||
* \brief Process one common argument. |
||||
* |
||||
* \param state The common state describing the test window to create. |
||||
* \param index The index of the argument to process in argv[]. |
||||
* |
||||
* \returns The number of arguments processed (i.e. 1 for --fullscreen, 2 for --video [videodriver], or -1 on error. |
||||
*/ |
||||
int SDLTest_CommonArg(SDLTest_CommonState * state, int index); |
||||
|
||||
|
||||
/**
|
||||
* \brief Logs command line usage info. |
||||
* |
||||
* This logs the appropriate command line options for the subsystems in use |
||||
* plus other common options, and then any application-specific options. |
||||
* This uses the SDL_Log() function and splits up output to be friendly to |
||||
* 80-character-wide terminals. |
||||
* |
||||
* \param state The common state describing the test window for the app. |
||||
* \param argv0 argv[0], as passed to main/SDL_main. |
||||
* \param options an array of strings for application specific options. The last element of the array should be NULL. |
||||
*/ |
||||
void SDLTest_CommonLogUsage(SDLTest_CommonState * state, const char *argv0, const char **options); |
||||
|
||||
/**
|
||||
* \brief Open test window. |
||||
* |
||||
* \param state The common state describing the test window to create. |
||||
* |
||||
* \returns True if initialization succeeded, false otherwise |
||||
*/ |
||||
SDL_bool SDLTest_CommonInit(SDLTest_CommonState * state); |
||||
|
||||
/**
|
||||
* \brief Easy argument handling when test app doesn't need any custom args. |
||||
* |
||||
* \param state The common state describing the test window to create. |
||||
* \param argc argc, as supplied to SDL_main |
||||
* \param argv argv, as supplied to SDL_main |
||||
* |
||||
* \returns False if app should quit, true otherwise. |
||||
*/ |
||||
SDL_bool SDLTest_CommonDefaultArgs(SDLTest_CommonState * state, const int argc, char **argv); |
||||
|
||||
/**
|
||||
* \brief Common event handler for test windows. |
||||
* |
||||
* \param state The common state used to create test window. |
||||
* \param event The event to handle. |
||||
* \param done Flag indicating we are done. |
||||
* |
||||
*/ |
||||
void SDLTest_CommonEvent(SDLTest_CommonState * state, SDL_Event * event, int *done); |
||||
|
||||
/**
|
||||
* \brief Close test window. |
||||
* |
||||
* \param state The common state used to create test window. |
||||
* |
||||
*/ |
||||
void SDLTest_CommonQuit(SDLTest_CommonState * state); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_common_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,69 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test_compare.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
/*
|
||||
|
||||
Defines comparison functions (i.e. for surfaces). |
||||
|
||||
*/ |
||||
|
||||
#ifndef SDL_test_compare_h_ |
||||
#define SDL_test_compare_h_ |
||||
|
||||
#include "SDL.h" |
||||
|
||||
#include "SDL_test_images.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief Compares a surface and with reference image data for equality |
||||
* |
||||
* \param surface Surface used in comparison |
||||
* \param referenceSurface Test Surface used in comparison |
||||
* \param allowable_error Allowable difference (=sum of squared difference for each RGB component) in blending accuracy. |
||||
* |
||||
* \returns 0 if comparison succeeded, >0 (=number of pixels for which the comparison failed) if comparison failed, -1 if any of the surfaces were NULL, -2 if the surface sizes differ. |
||||
*/ |
||||
int SDLTest_CompareSurfaces(SDL_Surface *surface, SDL_Surface *referenceSurface, int allowable_error); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_compare_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,124 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test_crc32.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
/*
|
||||
|
||||
Implements CRC32 calculations (default output is Perl String::CRC32 compatible). |
||||
|
||||
*/ |
||||
|
||||
#ifndef SDL_test_crc32_h_ |
||||
#define SDL_test_crc32_h_ |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
/* ------------ Definitions --------- */ |
||||
|
||||
/* Definition shared by all CRC routines */ |
||||
|
||||
#ifndef CrcUint32 |
||||
#define CrcUint32 unsigned int |
||||
#endif |
||||
#ifndef CrcUint8 |
||||
#define CrcUint8 unsigned char |
||||
#endif |
||||
|
||||
#ifdef ORIGINAL_METHOD |
||||
#define CRC32_POLY 0x04c11db7 /* AUTODIN II, Ethernet, & FDDI */ |
||||
#else |
||||
#define CRC32_POLY 0xEDB88320 /* Perl String::CRC32 compatible */ |
||||
#endif |
||||
|
||||
/**
|
||||
* Data structure for CRC32 (checksum) computation |
||||
*/ |
||||
typedef struct { |
||||
CrcUint32 crc32_table[256]; /* CRC table */ |
||||
} SDLTest_Crc32Context; |
||||
|
||||
/* ---------- Function Prototypes ------------- */ |
||||
|
||||
/**
|
||||
* \brief Initialize the CRC context |
||||
* |
||||
* Note: The function initializes the crc table required for all crc calculations. |
||||
* |
||||
* \param crcContext pointer to context variable |
||||
* |
||||
* \returns 0 for OK, -1 on error |
||||
* |
||||
*/ |
||||
int SDLTest_Crc32Init(SDLTest_Crc32Context * crcContext); |
||||
|
||||
|
||||
/**
|
||||
* \brief calculate a crc32 from a data block |
||||
* |
||||
* \param crcContext pointer to context variable |
||||
* \param inBuf input buffer to checksum |
||||
* \param inLen length of input buffer |
||||
* \param crc32 pointer to Uint32 to store the final CRC into |
||||
* |
||||
* \returns 0 for OK, -1 on error |
||||
* |
||||
*/ |
||||
int SDLTest_Crc32Calc(SDLTest_Crc32Context * crcContext, CrcUint8 *inBuf, CrcUint32 inLen, CrcUint32 *crc32); |
||||
|
||||
/* Same routine broken down into three steps */ |
||||
int SDLTest_Crc32CalcStart(SDLTest_Crc32Context * crcContext, CrcUint32 *crc32); |
||||
int SDLTest_Crc32CalcEnd(SDLTest_Crc32Context * crcContext, CrcUint32 *crc32); |
||||
int SDLTest_Crc32CalcBuffer(SDLTest_Crc32Context * crcContext, CrcUint8 *inBuf, CrcUint32 inLen, CrcUint32 *crc32); |
||||
|
||||
|
||||
/**
|
||||
* \brief clean up CRC context |
||||
* |
||||
* \param crcContext pointer to context variable |
||||
* |
||||
* \returns 0 for OK, -1 on error |
||||
* |
||||
*/ |
||||
|
||||
int SDLTest_Crc32Done(SDLTest_Crc32Context * crcContext); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_crc32_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,81 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test_font.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
#ifndef SDL_test_font_h_ |
||||
#define SDL_test_font_h_ |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* Function prototypes */ |
||||
|
||||
#define FONT_CHARACTER_SIZE 8 |
||||
|
||||
/**
|
||||
* \brief Draw a string in the currently set font. |
||||
* |
||||
* \param renderer The renderer to draw on. |
||||
* \param x The X coordinate of the upper left corner of the character. |
||||
* \param y The Y coordinate of the upper left corner of the character. |
||||
* \param c The character to draw. |
||||
* |
||||
* \returns Returns 0 on success, -1 on failure. |
||||
*/ |
||||
int SDLTest_DrawCharacter(SDL_Renderer *renderer, int x, int y, char c); |
||||
|
||||
/**
|
||||
* \brief Draw a string in the currently set font. |
||||
* |
||||
* \param renderer The renderer to draw on. |
||||
* \param x The X coordinate of the upper left corner of the string. |
||||
* \param y The Y coordinate of the upper left corner of the string. |
||||
* \param s The string to draw. |
||||
* |
||||
* \returns Returns 0 on success, -1 on failure. |
||||
*/ |
||||
int SDLTest_DrawString(SDL_Renderer *renderer, int x, int y, const char *s); |
||||
|
||||
|
||||
/**
|
||||
* \brief Cleanup textures used by font drawing functions. |
||||
*/ |
||||
void SDLTest_CleanupTextDrawing(void); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_font_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,384 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test_fuzzer.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
/*
|
||||
|
||||
Data generators for fuzzing test data in a reproducible way. |
||||
|
||||
*/ |
||||
|
||||
#ifndef SDL_test_fuzzer_h_ |
||||
#define SDL_test_fuzzer_h_ |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
/*
|
||||
Based on GSOC code by Markus Kauppila <markus.kauppila@gmail.com> |
||||
*/ |
||||
|
||||
|
||||
/**
|
||||
* \file |
||||
* Note: The fuzzer implementation uses a static instance of random context |
||||
* internally which makes it thread-UNsafe. |
||||
*/ |
||||
|
||||
/**
|
||||
* Initializes the fuzzer for a test |
||||
* |
||||
* \param execKey Execution "Key" that initializes the random number generator uniquely for the test. |
||||
* |
||||
*/ |
||||
void SDLTest_FuzzerInit(Uint64 execKey); |
||||
|
||||
|
||||
/**
|
||||
* Returns a random Uint8 |
||||
* |
||||
* \returns Generated integer |
||||
*/ |
||||
Uint8 SDLTest_RandomUint8(void); |
||||
|
||||
/**
|
||||
* Returns a random Sint8 |
||||
* |
||||
* \returns Generated signed integer |
||||
*/ |
||||
Sint8 SDLTest_RandomSint8(void); |
||||
|
||||
|
||||
/**
|
||||
* Returns a random Uint16 |
||||
* |
||||
* \returns Generated integer |
||||
*/ |
||||
Uint16 SDLTest_RandomUint16(void); |
||||
|
||||
/**
|
||||
* Returns a random Sint16 |
||||
* |
||||
* \returns Generated signed integer |
||||
*/ |
||||
Sint16 SDLTest_RandomSint16(void); |
||||
|
||||
|
||||
/**
|
||||
* Returns a random integer |
||||
* |
||||
* \returns Generated integer |
||||
*/ |
||||
Sint32 SDLTest_RandomSint32(void); |
||||
|
||||
|
||||
/**
|
||||
* Returns a random positive integer |
||||
* |
||||
* \returns Generated integer |
||||
*/ |
||||
Uint32 SDLTest_RandomUint32(void); |
||||
|
||||
/**
|
||||
* Returns random Uint64. |
||||
* |
||||
* \returns Generated integer |
||||
*/ |
||||
Uint64 SDLTest_RandomUint64(void); |
||||
|
||||
|
||||
/**
|
||||
* Returns random Sint64. |
||||
* |
||||
* \returns Generated signed integer |
||||
*/ |
||||
Sint64 SDLTest_RandomSint64(void); |
||||
|
||||
/**
|
||||
* \returns random float in range [0.0 - 1.0[ |
||||
*/ |
||||
float SDLTest_RandomUnitFloat(void); |
||||
|
||||
/**
|
||||
* \returns random double in range [0.0 - 1.0[ |
||||
*/ |
||||
double SDLTest_RandomUnitDouble(void); |
||||
|
||||
/**
|
||||
* \returns random float. |
||||
* |
||||
*/ |
||||
float SDLTest_RandomFloat(void); |
||||
|
||||
/**
|
||||
* \returns random double. |
||||
* |
||||
*/ |
||||
double SDLTest_RandomDouble(void); |
||||
|
||||
/**
|
||||
* Returns a random boundary value for Uint8 within the given boundaries. |
||||
* Boundaries are inclusive, see the usage examples below. If validDomain |
||||
* is true, the function will only return valid boundaries, otherwise non-valid |
||||
* boundaries are also possible. |
||||
* If boundary1 > boundary2, the values are swapped |
||||
* |
||||
* Usage examples: |
||||
* RandomUint8BoundaryValue(10, 20, SDL_TRUE) returns 10, 11, 19 or 20 |
||||
* RandomUint8BoundaryValue(1, 20, SDL_FALSE) returns 0 or 21 |
||||
* RandomUint8BoundaryValue(0, 99, SDL_FALSE) returns 100 |
||||
* RandomUint8BoundaryValue(0, 255, SDL_FALSE) returns 0 (error set) |
||||
* |
||||
* \param boundary1 Lower boundary limit |
||||
* \param boundary2 Upper boundary limit |
||||
* \param validDomain Should the generated boundary be valid (=within the bounds) or not? |
||||
* |
||||
* \returns Random boundary value for the given range and domain or 0 with error set |
||||
*/ |
||||
Uint8 SDLTest_RandomUint8BoundaryValue(Uint8 boundary1, Uint8 boundary2, SDL_bool validDomain); |
||||
|
||||
/**
|
||||
* Returns a random boundary value for Uint16 within the given boundaries. |
||||
* Boundaries are inclusive, see the usage examples below. If validDomain |
||||
* is true, the function will only return valid boundaries, otherwise non-valid |
||||
* boundaries are also possible. |
||||
* If boundary1 > boundary2, the values are swapped |
||||
* |
||||
* Usage examples: |
||||
* RandomUint16BoundaryValue(10, 20, SDL_TRUE) returns 10, 11, 19 or 20 |
||||
* RandomUint16BoundaryValue(1, 20, SDL_FALSE) returns 0 or 21 |
||||
* RandomUint16BoundaryValue(0, 99, SDL_FALSE) returns 100 |
||||
* RandomUint16BoundaryValue(0, 0xFFFF, SDL_FALSE) returns 0 (error set) |
||||
* |
||||
* \param boundary1 Lower boundary limit |
||||
* \param boundary2 Upper boundary limit |
||||
* \param validDomain Should the generated boundary be valid (=within the bounds) or not? |
||||
* |
||||
* \returns Random boundary value for the given range and domain or 0 with error set |
||||
*/ |
||||
Uint16 SDLTest_RandomUint16BoundaryValue(Uint16 boundary1, Uint16 boundary2, SDL_bool validDomain); |
||||
|
||||
/**
|
||||
* Returns a random boundary value for Uint32 within the given boundaries. |
||||
* Boundaries are inclusive, see the usage examples below. If validDomain |
||||
* is true, the function will only return valid boundaries, otherwise non-valid |
||||
* boundaries are also possible. |
||||
* If boundary1 > boundary2, the values are swapped |
||||
* |
||||
* Usage examples: |
||||
* RandomUint32BoundaryValue(10, 20, SDL_TRUE) returns 10, 11, 19 or 20 |
||||
* RandomUint32BoundaryValue(1, 20, SDL_FALSE) returns 0 or 21 |
||||
* RandomUint32BoundaryValue(0, 99, SDL_FALSE) returns 100 |
||||
* RandomUint32BoundaryValue(0, 0xFFFFFFFF, SDL_FALSE) returns 0 (with error set) |
||||
* |
||||
* \param boundary1 Lower boundary limit |
||||
* \param boundary2 Upper boundary limit |
||||
* \param validDomain Should the generated boundary be valid (=within the bounds) or not? |
||||
* |
||||
* \returns Random boundary value for the given range and domain or 0 with error set |
||||
*/ |
||||
Uint32 SDLTest_RandomUint32BoundaryValue(Uint32 boundary1, Uint32 boundary2, SDL_bool validDomain); |
||||
|
||||
/**
|
||||
* Returns a random boundary value for Uint64 within the given boundaries. |
||||
* Boundaries are inclusive, see the usage examples below. If validDomain |
||||
* is true, the function will only return valid boundaries, otherwise non-valid |
||||
* boundaries are also possible. |
||||
* If boundary1 > boundary2, the values are swapped |
||||
* |
||||
* Usage examples: |
||||
* RandomUint64BoundaryValue(10, 20, SDL_TRUE) returns 10, 11, 19 or 20 |
||||
* RandomUint64BoundaryValue(1, 20, SDL_FALSE) returns 0 or 21 |
||||
* RandomUint64BoundaryValue(0, 99, SDL_FALSE) returns 100 |
||||
* RandomUint64BoundaryValue(0, 0xFFFFFFFFFFFFFFFF, SDL_FALSE) returns 0 (with error set) |
||||
* |
||||
* \param boundary1 Lower boundary limit |
||||
* \param boundary2 Upper boundary limit |
||||
* \param validDomain Should the generated boundary be valid (=within the bounds) or not? |
||||
* |
||||
* \returns Random boundary value for the given range and domain or 0 with error set |
||||
*/ |
||||
Uint64 SDLTest_RandomUint64BoundaryValue(Uint64 boundary1, Uint64 boundary2, SDL_bool validDomain); |
||||
|
||||
/**
|
||||
* Returns a random boundary value for Sint8 within the given boundaries. |
||||
* Boundaries are inclusive, see the usage examples below. If validDomain |
||||
* is true, the function will only return valid boundaries, otherwise non-valid |
||||
* boundaries are also possible. |
||||
* If boundary1 > boundary2, the values are swapped |
||||
* |
||||
* Usage examples: |
||||
* RandomSint8BoundaryValue(-10, 20, SDL_TRUE) returns -11, -10, 19 or 20 |
||||
* RandomSint8BoundaryValue(-100, -10, SDL_FALSE) returns -101 or -9 |
||||
* RandomSint8BoundaryValue(SINT8_MIN, 99, SDL_FALSE) returns 100 |
||||
* RandomSint8BoundaryValue(SINT8_MIN, SINT8_MAX, SDL_FALSE) returns SINT8_MIN (== error value) with error set |
||||
* |
||||
* \param boundary1 Lower boundary limit |
||||
* \param boundary2 Upper boundary limit |
||||
* \param validDomain Should the generated boundary be valid (=within the bounds) or not? |
||||
* |
||||
* \returns Random boundary value for the given range and domain or SINT8_MIN with error set |
||||
*/ |
||||
Sint8 SDLTest_RandomSint8BoundaryValue(Sint8 boundary1, Sint8 boundary2, SDL_bool validDomain); |
||||
|
||||
|
||||
/**
|
||||
* Returns a random boundary value for Sint16 within the given boundaries. |
||||
* Boundaries are inclusive, see the usage examples below. If validDomain |
||||
* is true, the function will only return valid boundaries, otherwise non-valid |
||||
* boundaries are also possible. |
||||
* If boundary1 > boundary2, the values are swapped |
||||
* |
||||
* Usage examples: |
||||
* RandomSint16BoundaryValue(-10, 20, SDL_TRUE) returns -11, -10, 19 or 20 |
||||
* RandomSint16BoundaryValue(-100, -10, SDL_FALSE) returns -101 or -9 |
||||
* RandomSint16BoundaryValue(SINT16_MIN, 99, SDL_FALSE) returns 100 |
||||
* RandomSint16BoundaryValue(SINT16_MIN, SINT16_MAX, SDL_FALSE) returns SINT16_MIN (== error value) with error set |
||||
* |
||||
* \param boundary1 Lower boundary limit |
||||
* \param boundary2 Upper boundary limit |
||||
* \param validDomain Should the generated boundary be valid (=within the bounds) or not? |
||||
* |
||||
* \returns Random boundary value for the given range and domain or SINT16_MIN with error set |
||||
*/ |
||||
Sint16 SDLTest_RandomSint16BoundaryValue(Sint16 boundary1, Sint16 boundary2, SDL_bool validDomain); |
||||
|
||||
/**
|
||||
* Returns a random boundary value for Sint32 within the given boundaries. |
||||
* Boundaries are inclusive, see the usage examples below. If validDomain |
||||
* is true, the function will only return valid boundaries, otherwise non-valid |
||||
* boundaries are also possible. |
||||
* If boundary1 > boundary2, the values are swapped |
||||
* |
||||
* Usage examples: |
||||
* RandomSint32BoundaryValue(-10, 20, SDL_TRUE) returns -11, -10, 19 or 20 |
||||
* RandomSint32BoundaryValue(-100, -10, SDL_FALSE) returns -101 or -9 |
||||
* RandomSint32BoundaryValue(SINT32_MIN, 99, SDL_FALSE) returns 100 |
||||
* RandomSint32BoundaryValue(SINT32_MIN, SINT32_MAX, SDL_FALSE) returns SINT32_MIN (== error value) |
||||
* |
||||
* \param boundary1 Lower boundary limit |
||||
* \param boundary2 Upper boundary limit |
||||
* \param validDomain Should the generated boundary be valid (=within the bounds) or not? |
||||
* |
||||
* \returns Random boundary value for the given range and domain or SINT32_MIN with error set |
||||
*/ |
||||
Sint32 SDLTest_RandomSint32BoundaryValue(Sint32 boundary1, Sint32 boundary2, SDL_bool validDomain); |
||||
|
||||
/**
|
||||
* Returns a random boundary value for Sint64 within the given boundaries. |
||||
* Boundaries are inclusive, see the usage examples below. If validDomain |
||||
* is true, the function will only return valid boundaries, otherwise non-valid |
||||
* boundaries are also possible. |
||||
* If boundary1 > boundary2, the values are swapped |
||||
* |
||||
* Usage examples: |
||||
* RandomSint64BoundaryValue(-10, 20, SDL_TRUE) returns -11, -10, 19 or 20 |
||||
* RandomSint64BoundaryValue(-100, -10, SDL_FALSE) returns -101 or -9 |
||||
* RandomSint64BoundaryValue(SINT64_MIN, 99, SDL_FALSE) returns 100 |
||||
* RandomSint64BoundaryValue(SINT64_MIN, SINT64_MAX, SDL_FALSE) returns SINT64_MIN (== error value) and error set |
||||
* |
||||
* \param boundary1 Lower boundary limit |
||||
* \param boundary2 Upper boundary limit |
||||
* \param validDomain Should the generated boundary be valid (=within the bounds) or not? |
||||
* |
||||
* \returns Random boundary value for the given range and domain or SINT64_MIN with error set |
||||
*/ |
||||
Sint64 SDLTest_RandomSint64BoundaryValue(Sint64 boundary1, Sint64 boundary2, SDL_bool validDomain); |
||||
|
||||
|
||||
/**
|
||||
* Returns integer in range [min, max] (inclusive). |
||||
* Min and max values can be negative values. |
||||
* If Max in smaller than min, then the values are swapped. |
||||
* Min and max are the same value, that value will be returned. |
||||
* |
||||
* \param min Minimum inclusive value of returned random number |
||||
* \param max Maximum inclusive value of returned random number |
||||
* |
||||
* \returns Generated random integer in range |
||||
*/ |
||||
Sint32 SDLTest_RandomIntegerInRange(Sint32 min, Sint32 max); |
||||
|
||||
|
||||
/**
|
||||
* Generates random null-terminated string. The minimum length for |
||||
* the string is 1 character, maximum length for the string is 255 |
||||
* characters and it can contain ASCII characters from 32 to 126. |
||||
* |
||||
* Note: Returned string needs to be deallocated. |
||||
* |
||||
* \returns Newly allocated random string; or NULL if length was invalid or string could not be allocated. |
||||
*/ |
||||
char * SDLTest_RandomAsciiString(void); |
||||
|
||||
|
||||
/**
|
||||
* Generates random null-terminated string. The maximum length for |
||||
* the string is defined by the maxLength parameter. |
||||
* String can contain ASCII characters from 32 to 126. |
||||
* |
||||
* Note: Returned string needs to be deallocated. |
||||
* |
||||
* \param maxLength The maximum length of the generated string. |
||||
* |
||||
* \returns Newly allocated random string; or NULL if maxLength was invalid or string could not be allocated. |
||||
*/ |
||||
char * SDLTest_RandomAsciiStringWithMaximumLength(int maxLength); |
||||
|
||||
|
||||
/**
|
||||
* Generates random null-terminated string. The length for |
||||
* the string is defined by the size parameter. |
||||
* String can contain ASCII characters from 32 to 126. |
||||
* |
||||
* Note: Returned string needs to be deallocated. |
||||
* |
||||
* \param size The length of the generated string |
||||
* |
||||
* \returns Newly allocated random string; or NULL if size was invalid or string could not be allocated. |
||||
*/ |
||||
char * SDLTest_RandomAsciiStringOfSize(int size); |
||||
|
||||
/**
|
||||
* Returns the invocation count for the fuzzer since last ...FuzzerInit. |
||||
*/ |
||||
int SDLTest_GetFuzzerInvocationCount(void); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_fuzzer_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,134 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test_harness.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
/*
|
||||
Defines types for test case definitions and the test execution harness API. |
||||
|
||||
Based on original GSOC code by Markus Kauppila <markus.kauppila@gmail.com> |
||||
*/ |
||||
|
||||
#ifndef SDL_test_h_arness_h |
||||
#define SDL_test_h_arness_h |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
/* ! Definitions for test case structures */ |
||||
#define TEST_ENABLED 1 |
||||
#define TEST_DISABLED 0 |
||||
|
||||
/* ! Definition of all the possible test return values of the test case method */ |
||||
#define TEST_ABORTED -1 |
||||
#define TEST_STARTED 0 |
||||
#define TEST_COMPLETED 1 |
||||
#define TEST_SKIPPED 2 |
||||
|
||||
/* ! Definition of all the possible test results for the harness */ |
||||
#define TEST_RESULT_PASSED 0 |
||||
#define TEST_RESULT_FAILED 1 |
||||
#define TEST_RESULT_NO_ASSERT 2 |
||||
#define TEST_RESULT_SKIPPED 3 |
||||
#define TEST_RESULT_SETUP_FAILURE 4 |
||||
|
||||
/* !< Function pointer to a test case setup function (run before every test) */ |
||||
typedef void (*SDLTest_TestCaseSetUpFp)(void *arg); |
||||
|
||||
/* !< Function pointer to a test case function */ |
||||
typedef int (*SDLTest_TestCaseFp)(void *arg); |
||||
|
||||
/* !< Function pointer to a test case teardown function (run after every test) */ |
||||
typedef void (*SDLTest_TestCaseTearDownFp)(void *arg); |
||||
|
||||
/**
|
||||
* Holds information about a single test case. |
||||
*/ |
||||
typedef struct SDLTest_TestCaseReference { |
||||
/* !< Func2Stress */ |
||||
SDLTest_TestCaseFp testCase; |
||||
/* !< Short name (or function name) "Func2Stress" */ |
||||
char *name; |
||||
/* !< Long name or full description "This test pushes func2() to the limit." */ |
||||
char *description; |
||||
/* !< Set to TEST_ENABLED or TEST_DISABLED (test won't be run) */ |
||||
int enabled; |
||||
} SDLTest_TestCaseReference; |
||||
|
||||
/**
|
||||
* Holds information about a test suite (multiple test cases). |
||||
*/ |
||||
typedef struct SDLTest_TestSuiteReference { |
||||
/* !< "PlatformSuite" */ |
||||
char *name; |
||||
/* !< The function that is run before each test. NULL skips. */ |
||||
SDLTest_TestCaseSetUpFp testSetUp; |
||||
/* !< The test cases that are run as part of the suite. Last item should be NULL. */ |
||||
const SDLTest_TestCaseReference **testCases; |
||||
/* !< The function that is run after each test. NULL skips. */ |
||||
SDLTest_TestCaseTearDownFp testTearDown; |
||||
} SDLTest_TestSuiteReference; |
||||
|
||||
|
||||
/**
|
||||
* \brief Generates a random run seed string for the harness. The generated seed will contain alphanumeric characters (0-9A-Z). |
||||
* |
||||
* Note: The returned string needs to be deallocated by the caller. |
||||
* |
||||
* \param length The length of the seed string to generate |
||||
* |
||||
* \returns The generated seed string |
||||
*/ |
||||
char *SDLTest_GenerateRunSeed(const int length); |
||||
|
||||
/**
|
||||
* \brief Execute a test suite using the given run seed and execution key. |
||||
* |
||||
* \param testSuites Suites containing the test case. |
||||
* \param userRunSeed Custom run seed provided by user, or NULL to autogenerate one. |
||||
* \param userExecKey Custom execution key provided by user, or 0 to autogenerate one. |
||||
* \param filter Filter specification. NULL disables. Case sensitive. |
||||
* \param testIterations Number of iterations to run each test case. |
||||
* |
||||
* \returns Test run result; 0 when all tests passed, 1 if any tests failed. |
||||
*/ |
||||
int SDLTest_RunSuites(SDLTest_TestSuiteReference *testSuites[], const char *userRunSeed, Uint64 userExecKey, const char *filter, int testIterations); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_h_arness_h */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,78 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test_images.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
/*
|
||||
|
||||
Defines some images for tests. |
||||
|
||||
*/ |
||||
|
||||
#ifndef SDL_test_images_h_ |
||||
#define SDL_test_images_h_ |
||||
|
||||
#include "SDL.h" |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
*Type for test images. |
||||
*/ |
||||
typedef struct SDLTest_SurfaceImage_s { |
||||
int width; |
||||
int height; |
||||
unsigned int bytes_per_pixel; /* 3:RGB, 4:RGBA */ |
||||
const char *pixel_data; |
||||
} SDLTest_SurfaceImage_t; |
||||
|
||||
/* Test images */ |
||||
SDL_Surface *SDLTest_ImageBlit(void); |
||||
SDL_Surface *SDLTest_ImageBlitColor(void); |
||||
SDL_Surface *SDLTest_ImageBlitAlpha(void); |
||||
SDL_Surface *SDLTest_ImageBlitBlendAdd(void); |
||||
SDL_Surface *SDLTest_ImageBlitBlend(void); |
||||
SDL_Surface *SDLTest_ImageBlitBlendMod(void); |
||||
SDL_Surface *SDLTest_ImageBlitBlendNone(void); |
||||
SDL_Surface *SDLTest_ImageBlitBlendAll(void); |
||||
SDL_Surface *SDLTest_ImageFace(void); |
||||
SDL_Surface *SDLTest_ImagePrimitives(void); |
||||
SDL_Surface *SDLTest_ImagePrimitivesBlend(void); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_images_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,67 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test_log.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
/*
|
||||
* |
||||
* Wrapper to log in the TEST category |
||||
* |
||||
*/ |
||||
|
||||
#ifndef SDL_test_log_h_ |
||||
#define SDL_test_log_h_ |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* \brief Prints given message with a timestamp in the TEST category and INFO priority. |
||||
* |
||||
* \param fmt Message to be logged |
||||
*/ |
||||
void SDLTest_Log(SDL_PRINTF_FORMAT_STRING const char *fmt, ...) SDL_PRINTF_VARARG_FUNC(1); |
||||
|
||||
/**
|
||||
* \brief Prints given message with a timestamp in the TEST category and the ERROR priority. |
||||
* |
||||
* \param fmt Message to be logged |
||||
*/ |
||||
void SDLTest_LogError(SDL_PRINTF_FORMAT_STRING const char *fmt, ...) SDL_PRINTF_VARARG_FUNC(1); |
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_log_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,129 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test_md5.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
/*
|
||||
*********************************************************************** |
||||
** Header file for implementation of MD5 ** |
||||
** RSA Data Security, Inc. MD5 Message-Digest Algorithm ** |
||||
** Created: 2/17/90 RLR ** |
||||
** Revised: 12/27/90 SRD,AJ,BSK,JT Reference C version ** |
||||
** Revised (for MD5): RLR 4/27/91 ** |
||||
** -- G modified to have y&~z instead of y&z ** |
||||
** -- FF, GG, HH modified to add in last register done ** |
||||
** -- Access pattern: round 2 works mod 5, round 3 works mod 3 ** |
||||
** -- distinct additive constant for each step ** |
||||
** -- round 4 added, working mod 7 ** |
||||
*********************************************************************** |
||||
*/ |
||||
|
||||
/*
|
||||
*********************************************************************** |
||||
** Message-digest routines: ** |
||||
** To form the message digest for a message M ** |
||||
** (1) Initialize a context buffer mdContext using MD5Init ** |
||||
** (2) Call MD5Update on mdContext and M ** |
||||
** (3) Call MD5Final on mdContext ** |
||||
** The message digest is now in mdContext->digest[0...15] ** |
||||
*********************************************************************** |
||||
*/ |
||||
|
||||
#ifndef SDL_test_md5_h_ |
||||
#define SDL_test_md5_h_ |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* ------------ Definitions --------- */ |
||||
|
||||
/* typedef a 32-bit type */ |
||||
typedef unsigned long int MD5UINT4; |
||||
|
||||
/* Data structure for MD5 (Message-Digest) computation */ |
||||
typedef struct { |
||||
MD5UINT4 i[2]; /* number of _bits_ handled mod 2^64 */ |
||||
MD5UINT4 buf[4]; /* scratch buffer */ |
||||
unsigned char in[64]; /* input buffer */ |
||||
unsigned char digest[16]; /* actual digest after Md5Final call */ |
||||
} SDLTest_Md5Context; |
||||
|
||||
/* ---------- Function Prototypes ------------- */ |
||||
|
||||
/**
|
||||
* \brief initialize the context |
||||
* |
||||
* \param mdContext pointer to context variable |
||||
* |
||||
* Note: The function initializes the message-digest context |
||||
* mdContext. Call before each new use of the context - |
||||
* all fields are set to zero. |
||||
*/ |
||||
void SDLTest_Md5Init(SDLTest_Md5Context * mdContext); |
||||
|
||||
|
||||
/**
|
||||
* \brief update digest from variable length data |
||||
* |
||||
* \param mdContext pointer to context variable |
||||
* \param inBuf pointer to data array/string |
||||
* \param inLen length of data array/string |
||||
* |
||||
* Note: The function updates the message-digest context to account |
||||
* for the presence of each of the characters inBuf[0..inLen-1] |
||||
* in the message whose digest is being computed. |
||||
*/ |
||||
|
||||
void SDLTest_Md5Update(SDLTest_Md5Context * mdContext, unsigned char *inBuf, |
||||
unsigned int inLen); |
||||
|
||||
|
||||
/**
|
||||
* \brief complete digest computation |
||||
* |
||||
* \param mdContext pointer to context variable |
||||
* |
||||
* Note: The function terminates the message-digest computation and |
||||
* ends with the desired message digest in mdContext.digest[0..15]. |
||||
* Always call before using the digest[] variable. |
||||
*/ |
||||
|
||||
void SDLTest_Md5Final(SDLTest_Md5Context * mdContext); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_md5_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,63 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test_memory.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
#ifndef SDL_test_memory_h_ |
||||
#define SDL_test_memory_h_ |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
|
||||
/**
|
||||
* \brief Start tracking SDL memory allocations |
||||
*
|
||||
* \note This should be called before any other SDL functions for complete tracking coverage |
||||
*/ |
||||
int SDLTest_TrackAllocations(void); |
||||
|
||||
/**
|
||||
* \brief Print a log of any outstanding allocations |
||||
* |
||||
* \note This can be called after SDL_Quit() |
||||
*/ |
||||
void SDLTest_LogAllocations(void); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_memory_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
@ -0,0 +1,115 @@ |
||||
/*
|
||||
Simple DirectMedia Layer |
||||
Copyright (C) 1997-2019 Sam Lantinga <slouken@libsdl.org> |
||||
|
||||
This software is provided 'as-is', without any express or implied |
||||
warranty. In no event will the authors be held liable for any damages |
||||
arising from the use of this software. |
||||
|
||||
Permission is granted to anyone to use this software for any purpose, |
||||
including commercial applications, and to alter it and redistribute it |
||||
freely, subject to the following restrictions: |
||||
|
||||
1. The origin of this software must not be misrepresented; you must not |
||||
claim that you wrote the original software. If you use this software |
||||
in a product, an acknowledgment in the product documentation would be |
||||
appreciated but is not required. |
||||
2. Altered source versions must be plainly marked as such, and must not be |
||||
misrepresented as being the original software. |
||||
3. This notice may not be removed or altered from any source distribution. |
||||
*/ |
||||
|
||||
/**
|
||||
* \file SDL_test_random.h |
||||
* |
||||
* Include file for SDL test framework. |
||||
* |
||||
* This code is a part of the SDL2_test library, not the main SDL library. |
||||
*/ |
||||
|
||||
/*
|
||||
|
||||
A "32-bit Multiply with carry random number generator. Very fast. |
||||
Includes a list of recommended multipliers. |
||||
|
||||
multiply-with-carry generator: x(n) = a*x(n-1) + carry mod 2^32. |
||||
period: (a*2^31)-1 |
||||
|
||||
*/ |
||||
|
||||
#ifndef SDL_test_random_h_ |
||||
#define SDL_test_random_h_ |
||||
|
||||
#include "begin_code.h" |
||||
/* Set up for C function definitions, even when using C++ */ |
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* --- Definitions */ |
||||
|
||||
/*
|
||||
* Macros that return a random number in a specific format. |
||||
*/ |
||||
#define SDLTest_RandomInt(c) ((int)SDLTest_Random(c)) |
||||
|
||||
/*
|
||||
* Context structure for the random number generator state. |
||||
*/ |
||||
typedef struct { |
||||
unsigned int a; |
||||
unsigned int x; |
||||
unsigned int c; |
||||
unsigned int ah; |
||||
unsigned int al; |
||||
} SDLTest_RandomContext; |
||||
|
||||
|
||||
/* --- Function prototypes */ |
||||
|
||||
/**
|
||||
* \brief Initialize random number generator with two integers. |
||||
* |
||||
* Note: The random sequence of numbers returned by ...Random() is the |
||||
* same for the same two integers and has a period of 2^31. |
||||
* |
||||
* \param rndContext pointer to context structure |
||||
* \param xi integer that defines the random sequence |
||||
* \param ci integer that defines the random sequence |
||||
* |
||||
*/ |
||||
void SDLTest_RandomInit(SDLTest_RandomContext * rndContext, unsigned int xi, |
||||
unsigned int ci); |
||||
|
||||
/**
|
||||
* \brief Initialize random number generator based on current system time. |
||||
* |
||||
* \param rndContext pointer to context structure |
||||
* |
||||
*/ |
||||
void SDLTest_RandomInitTime(SDLTest_RandomContext *rndContext); |
||||
|
||||
|
||||
/**
|
||||
* \brief Initialize random number generator based on current system time. |
||||
* |
||||
* Note: ...RandomInit() or ...RandomInitTime() must have been called |
||||
* before using this function. |
||||
* |
||||
* \param rndContext pointer to context structure |
||||
* |
||||
* \returns A random number (32bit unsigned integer) |
||||
* |
||||
*/ |
||||
unsigned int SDLTest_Random(SDLTest_RandomContext *rndContext); |
||||
|
||||
|
||||
/* Ends C function definitions when using C++ */ |
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#include "close_code.h" |
||||
|
||||
#endif /* SDL_test_random_h_ */ |
||||
|
||||
/* vi: set ts=4 sw=4 expandtab: */ |
||||
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in new issue