Namespaces | Classes | Typedefs | Functions | Variables
parallel_ode Namespace Reference

Namespaces

namespace  BatchTypes
namespace  ParallelFlags
namespace  ReduceTypes

Classes

class  BatchStrategy
class  BatchStrategyFactory
class  ColoringBatchStrategy
class  CompactReduceStrategy
class  CudaPGSSolver
class  GreedyBatchStrategy
class  OpenCLPGSSolver
class  OpenMPPGSSolver
class  ParallelPGSSolver
 The base solver class. More...
class  ReduceStrategy
 The base strategy class. More...
class  ReduceStrategyFactory
class  SequentialReduceStrategy
class  StridedReduceStrategy

Typedefs

typedef boost::unordered_map
< int, int > 
BatchMap
typedef std::multimap< int,
int, std::greater< int > > 
BatchMultimap
typedef BatchMultimap::iterator BatchMultimapIterator
typedef BatchTypes::BatchType BatchType
typedef ParallelFlags::ParallelFlag ParallelFlag
typedef ReduceTypes::ReduceType ReduceType

Functions

std::string extractDirectory (const std::string &path)
void oclInitializeKernels (cl_context cxGPUContext, cl_command_queue cqParamCommandQue)
void oclPGSReduce (cl_mem fc0_reduction, cl_mem fc1_reduction, ReduceStrategy *reduceStrategy)
void oclPGSReduce (cl_mem fc0, cl_mem fc1, cl_mem fc0_reduction, cl_mem fc1_reduction, ReduceStrategy *reduceStrategy)
void oclPGSSolve (int offset, int numConstraints, bool bUseAtomics)
void oclPGSSolveInit (cl_mem bodyIDs, cl_mem fIDs, cl_mem j, cl_mem ij, cl_mem fc0, cl_mem fc1, cl_mem fc0_reduction, cl_mem fc1_reduction, cl_mem lambda, cl_mem adcfm, cl_mem rhs, cl_mem hilo, int bStride, int cStride, ReduceStrategy *reduceStrategy)
void oclShutdownKernels (void)
void oclZeroVector (cl_mem buffer, int bufferSize, bool bScalarType)
template<typename T >
void ompPGSReduce (typename vec4< T >::Type *fc0, typename vec4< T >::Type *fc1, typename vec4< T >::Type *fc0_reduction, typename vec4< T >::Type *fc1_reduction, ReduceStrategy *reduceStrategy)
template void ompPGSReduce< dReal > (dReal4 *fc0, dReal4 *fc1, dReal4 *fc0_reduction, dReal4 *fc1_reduction, ReduceStrategy *reduceStrategy)
template<typename T >
void ompPGSSolve (int4 *bodyIDs, int *fIDs, typename vec4< T >::Type *j, typename vec4< T >::Type *ij, typename vec4< T >::Type *fc0, typename vec4< T >::Type *fc1, typename vec4< T >::Type *fc0_reduction, typename vec4< T >::Type *fc1_reduction, T *lambda, T *adcfm, T *rhs, T *hilo, int offset, int numConstraints, bool bUseAtomics, int bStride, int cStride)
template void ompPGSSolve< dReal > (int4 *bodyIDs, int *fIDs, dReal4 *j, dReal4 *ij, dReal4 *fc0, dReal4 *fc1, dReal4 *fc0_reduction, dReal4 *fc1_reduction, dReal *lambda, dReal *adcfm, dReal *rhs, dReal *hilo, int batch, int numConstraints, bool bUseAtomics, int bStride, int cStride)
template<typename T >
void ompZeroVector (T *buffer, int bufferSize)
template void ompZeroVector< dReal4 > (dReal4 *buffer, int bufferSize)
static size_t uSnap (size_t a, size_t b)

Variables

static cl_kernel ckReduce
static cl_kernel ckSolve
static cl_kernel ckZero
static cl_kernel ckZero4
static cl_program cpSolver
static cl_command_queue cqDefaultCommandQueue
static const int DEFAULT_CL_FLAGS
const int DEFAULT_FLAGS
 Default configuration flags for the base solver.
const int DEFAULT_OPENMP_FLAGS
static const std::string FILENAME = __FILE__
static const std::string INC_DIR = "/"
static const std::string SRC_DIR = extractDirectory( FILENAME )

Typedef Documentation

typedef boost::unordered_map<int, int> parallel_ode::BatchMap

Definition at line 13 of file parallel_batch.cpp.

typedef std::multimap<int, int, std::greater<int> > parallel_ode::BatchMultimap

Definition at line 14 of file parallel_batch.cpp.

typedef BatchMultimap::iterator parallel_ode::BatchMultimapIterator

Definition at line 15 of file parallel_batch.cpp.

Definition at line 17 of file parallel_batch.h.

Definition at line 34 of file parallel_solver.h.

Definition at line 18 of file parallel_reduce.h.


Function Documentation

std::string parallel_ode::extractDirectory ( const std::string &  path)

Extracts the directory from a given ptah

Parameters:
pathThe global path of a file
Returns:
A string containing the directory

Definition at line 40 of file opencl_kernels.cpp.

void parallel_ode::oclInitializeKernels ( cl_context  cxGPUContext,
cl_command_queue  cqParamCommandQue 
)

Definition at line 49 of file opencl_kernels.cpp.

void parallel_ode::oclPGSReduce ( cl_mem  fc0_reduction,
cl_mem  fc1_reduction,
ReduceStrategy *  reduceStrategy 
)

Definition at line 104 of file opencl_kernels.cpp.

void parallel_ode::oclPGSReduce ( cl_mem  fc0,
cl_mem  fc1,
cl_mem  fc0_reduction,
cl_mem  fc1_reduction,
ReduceStrategy *  reduceStrategy 
)

Definition at line 138 of file opencl_kernels.cpp.

void parallel_ode::oclPGSSolve ( int  offset,
int  numConstraints,
bool  bUseAtomics 
)

Definition at line 185 of file opencl_kernels.cpp.

void parallel_ode::oclPGSSolveInit ( cl_mem  bodyIDs,
cl_mem  fIDs,
cl_mem  j,
cl_mem  ij,
cl_mem  fc0,
cl_mem  fc1,
cl_mem  fc0_reduction,
cl_mem  fc1_reduction,
cl_mem  lambda,
cl_mem  adcfm,
cl_mem  rhs,
cl_mem  hilo,
int  bStride,
int  cStride,
ReduceStrategy *  reduceStrategy 
)

Definition at line 200 of file opencl_kernels.cpp.

Definition at line 94 of file opencl_kernels.cpp.

void parallel_ode::oclZeroVector ( cl_mem  buffer,
int  bufferSize,
bool  bScalarType 
)

Definition at line 162 of file opencl_kernels.cpp.

template<typename T >
void parallel_ode::ompPGSReduce ( typename vec4< T >::Type *  fc0,
typename vec4< T >::Type *  fc1,
typename vec4< T >::Type *  fc0_reduction,
typename vec4< T >::Type *  fc1_reduction,
ReduceStrategy *  reduceStrategy 
)

Definition at line 27 of file openmp_kernels.cpp.

template void parallel_ode::ompPGSReduce< dReal > ( dReal4 *  fc0,
dReal4 *  fc1,
dReal4 *  fc0_reduction,
dReal4 *  fc1_reduction,
ReduceStrategy *  reduceStrategy 
)
template<typename T >
void parallel_ode::ompPGSSolve ( int4 bodyIDs,
int *  fIDs,
typename vec4< T >::Type *  j,
typename vec4< T >::Type *  ij,
typename vec4< T >::Type *  fc0,
typename vec4< T >::Type *  fc1,
typename vec4< T >::Type *  fc0_reduction,
typename vec4< T >::Type *  fc1_reduction,
T *  lambda,
T *  adcfm,
T *  rhs,
T *  hilo,
int  offset,
int  numConstraints,
bool  bUseAtomics,
int  bStride,
int  cStride 
)

Definition at line 63 of file openmp_kernels.cpp.

template void parallel_ode::ompPGSSolve< dReal > ( int4 bodyIDs,
int *  fIDs,
dReal4 *  j,
dReal4 *  ij,
dReal4 *  fc0,
dReal4 *  fc1,
dReal4 *  fc0_reduction,
dReal4 *  fc1_reduction,
dReal *  lambda,
dReal *  adcfm,
dReal *  rhs,
dReal *  hilo,
int  batch,
int  numConstraints,
bool  bUseAtomics,
int  bStride,
int  cStride 
)
template<typename T >
void parallel_ode::ompZeroVector ( T *  buffer,
int  bufferSize 
)

Definition at line 17 of file openmp_kernels.cpp.

template void parallel_ode::ompZeroVector< dReal4 > ( dReal4 *  buffer,
int  bufferSize 
)
static size_t parallel_ode::uSnap ( size_t  a,
size_t  b 
) [static]

Aligns a to the next largest multiple of b

Parameters:
athe parameter to align
bthe alignment
Returns:
the aligned size

Definition at line 21 of file opencl_kernels.cpp.


Variable Documentation

cl_kernel parallel_ode::ckReduce [static]

The reduction kernel

Definition at line 26 of file opencl_kernels.cpp.

cl_kernel parallel_ode::ckSolve [static]

The solution kernel

Definition at line 26 of file opencl_kernels.cpp.

cl_kernel parallel_ode::ckZero [static]

The clearing kernel for scalar values

Definition at line 26 of file opencl_kernels.cpp.

cl_kernel parallel_ode::ckZero4 [static]

The clearing kernel for vec4 values

Definition at line 26 of file opencl_kernels.cpp.

cl_program parallel_ode::cpSolver [static]

OpenCL solver program

Definition at line 11 of file opencl_kernels.cpp.

cl_command_queue parallel_ode::cqDefaultCommandQueue [static]

Local storage of global command queue

Definition at line 31 of file opencl_kernels.cpp.

const int parallel_ode::DEFAULT_CL_FLAGS [static]
const std::string parallel_ode::FILENAME = __FILE__ [static]

This file name, as a global path

Definition at line 45 of file opencl_kernels.cpp.

const std::string parallel_ode::INC_DIR = "/" [static]

The directory of includes

Definition at line 47 of file opencl_kernels.cpp.

const std::string parallel_ode::SRC_DIR = extractDirectory( FILENAME ) [static]

The directory of this file

Definition at line 46 of file opencl_kernels.cpp.



parallel_quickstep
Author(s): Jared Duke
autogenerated on Fri Jan 3 2014 11:36:56