00001 #include <parallel_batch.h>
00002 #include <parallel_utils.h>
00003
00004 #include <map>
00005 #include <boost/unordered_map.hpp>
00006
00007 namespace parallel_ode
00008 {
00009
00010 using ::parallel_utils::permuteVector;
00011 using ::parallel_utils::fillSequentialVector;
00012
00013 typedef boost::unordered_map<int, int> BatchMap;
00014 typedef std::multimap<int, int, std::greater<int> > BatchMultimap;
00015 typedef BatchMultimap::iterator BatchMultimapIterator;
00016
00017 int BatchStrategy::baseBatch( const int* pairList,
00018 const BatchVector& constraintIndices,
00019 const BatchVector& batchSizes,
00020 BatchVector& batchIndices,
00021 BatchVector& bodyRepetitionCount0,
00022 BatchVector& bodyRepetitionCount1,
00023 BatchVector& maxBodyRepetitionCount )
00024 {
00025 batchIndicesFromBatchSizes( batchSizes, batchIndices, isAligning( ), getAlignment( ) );
00026
00027 return batchRepetitionCount( pairList, constraintIndices, batchSizes, bodyRepetitionCount0, bodyRepetitionCount1, maxBodyRepetitionCount );
00028 }
00029
00030 void BatchStrategy::batchIndicesFromBatchSizes( const BatchVector& batchSizes, BatchVector& batchIndices, bool bAlign, int alignment )
00031 {
00032 batchIndices.resize( batchSizes.size() );
00033
00034 for( size_t batchID = 0, batchOffset = 0; batchID < batchSizes.size(); batchID++ )
00035 {
00036 if( bAlign ) alignOffset( batchOffset, alignment );
00037 batchIndices[ batchID ] = batchOffset;
00038 batchOffset += batchSizes[ batchID ];
00039 }
00040 }
00041
00042 int BatchStrategy::batchRepetitionCount( const int *pairList,
00043 const BatchVector& constraintIndices,
00044 const BatchVector& batchSizes,
00045 BatchVector& bodyRepetitionCount0,
00046 BatchVector& bodyRepetitionCount1,
00047 BatchVector& maxBodyRepetitionCountInBatch )
00048 {
00049 maxBodyRepetitionCountInBatch.resize( getMaxBatches() );
00050
00051 int maxRepetitionCount = 0;
00052 BatchVector bodyRepetitionMap( bodyRepetitionCount0.size() );
00053
00054 for( size_t batchID = 0, constraintID = 0; batchID < batchSizes.size(); batchID++ )
00055 {
00056 bodyRepetitionMap.assign( bodyRepetitionMap.size(), 0 );
00057 int maxRepetitionCountInBatch = 0;
00058
00059 for( int iter = 0; iter < batchSizes[ batchID ]; ++iter,++constraintID )
00060 {
00061 int bodyID0 = pairList[ constraintIndices[ constraintID ]*2 ] ;
00062 int bodyID1 = pairList[ constraintIndices[ constraintID ]*2+1 ] ;
00063
00064 if( bodyID0 >= 0 ) {
00065 bodyRepetitionCount0[ constraintID ] = bodyRepetitionMap[ bodyID0 ]++;
00066 maxRepetitionCountInBatch = std::max( maxRepetitionCountInBatch, bodyRepetitionMap[ bodyID0 ] );
00067 }
00068 if( bodyID1 >= 0 ) {
00069 bodyRepetitionCount1[ constraintID ] = bodyRepetitionMap[ bodyID1 ]++;
00070 maxRepetitionCountInBatch = std::max( maxRepetitionCountInBatch, bodyRepetitionMap[ bodyID1 ] );
00071 }
00072 }
00073
00074 maxBodyRepetitionCountInBatch[ batchID ] = maxRepetitionCountInBatch;
00075 maxRepetitionCount = std::max( maxRepetitionCount, maxRepetitionCountInBatch );
00076 }
00077
00078 return maxRepetitionCount;
00079 }
00080
00081 int BatchStrategy::batch( const int* pairList, const int numConstraints, const int numBodies,
00082 BatchVector& constraintIndices,
00083 BatchVector& bodyRepetitionCount0,
00084 BatchVector& bodyRepetitionCount1,
00085 BatchVector& maxBodyRepetitionCountInBatch,
00086 BatchVector& batchIndices,
00087 BatchVector& batchSizes )
00088 {
00089 batchSizes.resize( getMaxBatches() );
00090 batchSizes.assign( getMaxBatches(), 0 );
00091
00092
00093 fillSequentialVector( constraintIndices );
00094 permuteVector( constraintIndices );
00095
00096 const int batchSize = numConstraints / getMaxBatches( );
00097 batchSizes[ 0 ] = batchSize + ( numConstraints % batchSize );
00098 for( int batchID = 1; batchID < getMaxBatches(); ++batchID ) {
00099 batchSizes[ batchID ] = batchSize;
00100 }
00101
00102 return baseBatch( pairList, constraintIndices, batchSizes, batchIndices, bodyRepetitionCount0, bodyRepetitionCount1, maxBodyRepetitionCountInBatch );
00103 }
00104
00105 int GreedyBatchStrategy::batch( const int* pairList, const int numConstraints, const int numBodies,
00106 BatchVector& constraintIndices,
00107 BatchVector& bodyRepetitionCount0,
00108 BatchVector& bodyRepetitionCount1,
00109 BatchVector& maxBodyRepetitionCountInBatch,
00110 BatchVector& batchIndices,
00111 BatchVector& batchSizes )
00112 {
00113 int constraintsUsed = 0;
00114 std::vector<bool> constraintAssigned( numConstraints, false );
00115 std::vector<bool> bodyUsed( numBodies );
00116
00117 batchSizes.resize( getMaxBatches() );
00118 batchSizes.assign( getMaxBatches(), 0 );
00119 constraintIndices.assign( numConstraints, -1 );
00120
00121 int currentBatchSize = 0;
00122
00123
00124 do {
00125 for(int batchID = 0; batchID < getMaxBatches(); ++batchID)
00126 {
00127 currentBatchSize = 0;
00128 bodyUsed.assign( numBodies, false );
00129
00130 for(int constraintID = 0; constraintID < numConstraints; ++constraintID)
00131 {
00132 if( constraintAssigned[ constraintID ] ) continue;
00133
00134 const int b1 = pairList[ constraintID*2 ];
00135 const int b2 = pairList[ constraintID*2 + 1];
00136
00137 if((b1 < 0 || !bodyUsed[ b1 ]) && ( b2 < 0 || !bodyUsed[ b2 ]))
00138 {
00139 if( b1 >= 0 ) bodyUsed[ b1 ] = true;
00140 if( b2 >= 0 ) bodyUsed[ b2 ] = true;
00141 constraintAssigned[ constraintID ] = true;
00142 constraintIndices[ constraintID ] = batchID;
00143 ++constraintsUsed;
00144 ++currentBatchSize;
00145 }
00146 }
00147
00148 batchSizes[ batchID ] += currentBatchSize;
00149 }
00150 } while( constraintsUsed < numConstraints);
00151
00152 BatchVector batchSizesCopy = batchSizes;
00153 BatchVector constraintIndicesCopy = constraintIndices;
00154
00155
00156 for(int constraintID = 0; constraintID < numConstraints; ++constraintID) {
00157 const int constraintBatchID = constraintIndicesCopy[ constraintID ];
00158 const int newConstraintID = --batchSizesCopy[ constraintBatchID ];
00159 constraintIndices[ constraintID ] = newConstraintID;
00160 }
00161
00162 return baseBatch( pairList, constraintIndices, batchSizes, batchIndices, bodyRepetitionCount0, bodyRepetitionCount1, maxBodyRepetitionCountInBatch );
00163 }
00164
00165 int ColoringBatchStrategy::batch( const int* pairList, const int numConstraints, const int numBodies,
00166 BatchVector& constraintIndices,
00167 BatchVector& bodyRepetitionCount0,
00168 BatchVector& bodyRepetitionCount1,
00169 BatchVector& maxBodyRepetitionCountInBatch,
00170 BatchVector& batchIndices,
00171 BatchVector& batchSizes )
00172 {
00173 BatchMultimap bodyConstraintMap;
00174 BatchMultimap constraintHeap;
00175
00176 std::vector<BatchMultimapIterator> pointers( numConstraints );
00177 BatchVector colors( numConstraints, std::numeric_limits<int>::max() );
00178
00179 int maxDegree( 0 ), numColors( 1 ), degree;
00180
00181
00182 for( int constraintID = 0; constraintID < numConstraints; ++constraintID )
00183 {
00184 bodyConstraintMap.insert( std::make_pair( pairList[ constraintID*2 ], constraintID ) );
00185 bodyConstraintMap.insert( std::make_pair( pairList[ constraintID*2 + 1 ], constraintID ) );
00186 }
00187
00188
00189 for( int constraintID = 0; constraintID < numConstraints; ++constraintID ) {
00190 const int b1( pairList[ constraintID*2 ] );
00191 const int b2( pairList[ constraintID*2 + 1 ] );
00192
00193 int degree = 0;
00194
00195 if( b1 >= 0 && b2 >= 0)
00196 degree = bodyConstraintMap.count( b1 ) + bodyConstraintMap.count( b2 ) - 1;
00197 else if( b1 >= 0 )
00198 degree = bodyConstraintMap.count( b1 );
00199 else if( b2 >= 0 )
00200 degree = bodyConstraintMap.count( b2 );
00201
00202 if( degree > 0 ) {
00203 pointers[ constraintID ] = constraintHeap.insert( std::make_pair( degree, constraintID ) );
00204 maxDegree = std::max( maxDegree, degree );
00205 }
00206 }
00207
00208 BatchVector occurrences( getMaxBatches() );
00209 BatchVector colorCount( numColors, 0 );
00210
00211 while( !constraintHeap.empty() ) {
00212 int constraintID = constraintHeap.begin()->second;
00213 constraintHeap.erase( constraintHeap.begin() );
00214 occurrences.assign( numColors, 0 );
00215
00216 const int bodyIDs[2] = { pairList[ constraintID*2 ], pairList[ constraintID*2 + 1 ] };
00217
00218 for( int j = 0; j < 2; ++j) {
00219
00220 BatchMultimapIterator it = bodyConstraintMap.find( bodyIDs[ j ] );
00221 if( it == bodyConstraintMap.end() ) continue;
00222 BatchMultimapIterator end = bodyConstraintMap.upper_bound( bodyIDs[ j ] );
00223
00224 for(; it != end; ++it ) {
00225 int bodyConstraintID = it->second;
00226 if( bodyConstraintID == constraintID ) continue;
00227
00228 if( colors[ bodyConstraintID ] < numColors ) {
00229
00230 ++occurrences[ colors[ bodyConstraintID ] ];
00231 }
00232 else {
00233
00234 degree = pointers[ bodyConstraintID ]->first;
00235 if( pointers[bodyConstraintID] == constraintHeap.begin() ) {
00236 constraintHeap.erase( pointers[ bodyConstraintID ] );
00237 pointers[ bodyConstraintID ] = constraintHeap.insert( std::make_pair( degree - 1, bodyConstraintID ) );
00238 }
00239 else {
00240 constraintHeap.erase( pointers[ bodyConstraintID ]-- );
00241 pointers[ bodyConstraintID ] = constraintHeap.insert( pointers[ bodyConstraintID ], std::make_pair( degree - 1, bodyConstraintID ) );
00242 }
00243 }
00244 }
00245 }
00246
00247
00248 int minColor = 0;
00249 for( int colorID = 1; colorID < numColors; ++colorID )
00250 {
00251 if( ( occurrences[ colorID ] < occurrences[ minColor ] ) ||
00252 ( occurrences[ colorID ] == occurrences[ minColor ] && colorCount[ colorID ] < colorCount[ minColor ] ) )
00253 {
00254 minColor = colorID;
00255 }
00256 }
00257
00258 if( occurrences[ minColor ] > 0 && numColors < getMaxBatches() )
00259 {
00260 colors[ constraintID ] = numColors++;
00261 colorCount.resize( numColors );
00262 colorCount[ colors[ constraintID ] ] = 1;
00263 }
00264 else
00265 {
00266 colors[ constraintID ] = minColor;
00267 colorCount[ colors[ constraintID ] ]++;
00268 }
00269 }
00270
00271 batchSizes.resize( getMaxBatches(), 0 );
00272 batchSizes = colorCount;
00273 batchIndicesFromBatchSizes( batchSizes, batchIndices, isAligning( ), getAlignment( ) );
00274
00275
00276 for( int constraintID = 0; constraintID < numConstraints; ++constraintID ) {
00277 const int constraintBatchID = colors[ constraintID ];
00278 constraintIndices[ constraintID ] = batchIndices[ constraintBatchID ] + ( batchSizes[ constraintBatchID ] - colorCount[ constraintBatchID ] );
00279 --colorCount[ constraintBatchID ];
00280 }
00281
00282 return batchRepetitionCount( pairList, constraintIndices, batchSizes, bodyRepetitionCount0, bodyRepetitionCount1, maxBodyRepetitionCountInBatch );
00283 }
00284
00285 }