Skip to content

Commit bb5cfb2

Browse files
authored
Merge pull request #1912 from borglab/profiling
2 parents bbdeaa4 + a9c75d8 commit bb5cfb2

11 files changed

+122
-58
lines changed

cmake/FindGooglePerfTools.cmake

Lines changed: 25 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -1,42 +1,38 @@
11
# -*- cmake -*-
22

3-
# - Find Google perftools
4-
# Find the Google perftools includes and libraries
5-
# This module defines
6-
# GOOGLE_PERFTOOLS_INCLUDE_DIR, where to find heap-profiler.h, etc.
7-
# GOOGLE_PERFTOOLS_FOUND, If false, do not try to use Google perftools.
8-
# also defined for general use are
9-
# TCMALLOC_LIBRARY, where to find the tcmalloc library.
10-
11-
FIND_PATH(GOOGLE_PERFTOOLS_INCLUDE_DIR google/heap-profiler.h
12-
/usr/local/include
13-
/usr/include
14-
)
3+
# - Find GPerfTools (formerly Google perftools)
4+
# Find the GPerfTools libraries
5+
# If false, do not try to use Google perftools.
6+
# Also defined for general use are
7+
# - GPERFTOOLS_TCMALLOC: where to find the tcmalloc library
8+
# - GPERFTOOLS_PROFILER: where to find the profiler library
159

1610
SET(TCMALLOC_NAMES ${TCMALLOC_NAMES} tcmalloc)
17-
FIND_LIBRARY(TCMALLOC_LIBRARY
11+
find_library(GPERFTOOLS_TCMALLOC
1812
NAMES ${TCMALLOC_NAMES}
1913
PATHS /usr/lib /usr/local/lib
20-
)
14+
)
15+
find_library(GPERFTOOLS_PROFILER
16+
NAMES profiler
17+
PATHS /usr/lib /usr/local/lib
18+
)
2119

22-
IF (TCMALLOC_LIBRARY AND GOOGLE_PERFTOOLS_INCLUDE_DIR)
23-
SET(TCMALLOC_LIBRARIES ${TCMALLOC_LIBRARY})
24-
SET(GOOGLE_PERFTOOLS_FOUND "YES")
25-
ELSE (TCMALLOC_LIBRARY AND GOOGLE_PERFTOOLS_INCLUDE_DIR)
26-
SET(GOOGLE_PERFTOOLS_FOUND "NO")
27-
ENDIF (TCMALLOC_LIBRARY AND GOOGLE_PERFTOOLS_INCLUDE_DIR)
20+
IF (GPERFTOOLS_TCMALLOC AND GPERFTOOLS_PROFILER)
21+
SET(TCMALLOC_LIBRARIES ${GPERFTOOLS_TCMALLOC})
22+
SET(GPERFTOOLS_FOUND "YES")
23+
ELSE (GPERFTOOLS_TCMALLOC AND GPERFTOOLS_PROFILER)
24+
SET(GPERFTOOLS_FOUND "NO")
25+
ENDIF (GPERFTOOLS_TCMALLOC AND GPERFTOOLS_PROFILER)
2826

29-
IF (GOOGLE_PERFTOOLS_FOUND)
30-
IF (NOT GOOGLE_PERFTOOLS_FIND_QUIETLY)
31-
MESSAGE(STATUS "Found Google perftools: ${GOOGLE_PERFTOOLS_LIBRARIES}")
32-
ENDIF (NOT GOOGLE_PERFTOOLS_FIND_QUIETLY)
33-
ELSE (GOOGLE_PERFTOOLS_FOUND)
27+
IF (GPERFTOOLS_FOUND)
28+
MESSAGE(STATUS "Found Gperftools: ${GPERFTOOLS_PROFILER}")
29+
ELSE (GPERFTOOLS_FOUND)
3430
IF (GOOGLE_PERFTOOLS_FIND_REQUIRED)
3531
MESSAGE(FATAL_ERROR "Could not find Google perftools library")
3632
ENDIF (GOOGLE_PERFTOOLS_FIND_REQUIRED)
37-
ENDIF (GOOGLE_PERFTOOLS_FOUND)
33+
ENDIF (GPERFTOOLS_FOUND)
3834

3935
MARK_AS_ADVANCED(
40-
TCMALLOC_LIBRARY
41-
GOOGLE_PERFTOOLS_INCLUDE_DIR
42-
)
36+
GPERFTOOLS_TCMALLOC
37+
GPERFTOOLS_PROFILER
38+
)

cmake/HandleAllocators.cmake

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ else()
77
list(APPEND possible_allocators BoostPool STL)
88
set(preferred_allocator STL)
99
endif()
10-
if(GOOGLE_PERFTOOLS_FOUND)
10+
if(GPERFTOOLS_FOUND)
1111
list(APPEND possible_allocators tcmalloc)
1212
endif()
1313

cmake/HandlePerfTools.cmake

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
11

22
###############################################################################
33
# Find Google perftools
4-
find_package(GooglePerfTools)
4+
find_package(GooglePerfTools)

gtsam/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -147,6 +147,10 @@ if (GTSAM_USE_EIGEN_MKL)
147147
target_include_directories(gtsam PUBLIC ${MKL_INCLUDE_DIR})
148148
endif()
149149

150+
if (GPERFTOOLS_FOUND)
151+
target_link_libraries(gtsam PRIVATE ${GPERFTOOLS_TCMALLOC} ${GPERFTOOLS_PROFILER})
152+
endif()
153+
150154
# Add includes for source directories 'BEFORE' boost and any system include
151155
# paths so that the compiler uses GTSAM headers in our source directory instead
152156
# of any previously installed GTSAM headers.

gtsam/discrete/DecisionTreeFactor.cpp

Lines changed: 21 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -407,11 +407,9 @@ namespace gtsam {
407407
};
408408

409409
/* ************************************************************************ */
410-
DecisionTreeFactor DecisionTreeFactor::prune(size_t maxNrAssignments) const {
411-
const size_t N = maxNrAssignments;
412-
410+
double DecisionTreeFactor::computeThreshold(const size_t N) const {
413411
// Set of all keys
414-
std::set<Key> allKeys(keys().begin(), keys().end());
412+
std::set<Key> allKeys = this->labels();
415413
MinHeap min_heap;
416414

417415
auto op = [&](const Assignment<Key>& a, double p) {
@@ -433,26 +431,40 @@ namespace gtsam {
433431
nrAssignments *= cardinalities_.at(k);
434432
}
435433

434+
// If min-heap is empty, fill it initially.
435+
// This is because there is nothing at the top.
436436
if (min_heap.empty()) {
437437
min_heap.push(p, std::min(nrAssignments, N));
438438

439439
} else {
440-
// If p is larger than the smallest element,
441-
// then we insert into the max heap.
442-
if (p > min_heap.top()) {
443-
for (size_t i = 0; i < std::min(nrAssignments, N); ++i) {
440+
for (size_t i = 0; i < std::min(nrAssignments, N); ++i) {
441+
// If p is larger than the smallest element,
442+
// then we insert into the min heap.
443+
// We check against the top each time because the
444+
// heap maintains the smallest element at the top.
445+
if (p > min_heap.top()) {
444446
if (min_heap.size() == N) {
445447
min_heap.pop();
446448
}
447449
min_heap.push(p);
450+
} else {
451+
// p is <= min value so move to the next one
452+
break;
448453
}
449454
}
450455
}
451456
return p;
452457
};
453458
this->visitWith(op);
454459

455-
double threshold = min_heap.top();
460+
return min_heap.top();
461+
}
462+
463+
/* ************************************************************************ */
464+
DecisionTreeFactor DecisionTreeFactor::prune(size_t maxNrAssignments) const {
465+
const size_t N = maxNrAssignments;
466+
467+
double threshold = computeThreshold(N);
456468

457469
// Now threshold the decision tree
458470
size_t total = 0;

gtsam/discrete/DecisionTreeFactor.h

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -224,6 +224,17 @@ namespace gtsam {
224224
/// Get all the probabilities in order of assignment values
225225
std::vector<double> probabilities() const;
226226

227+
/**
228+
* @brief Compute the probability value which is the threshold above which
229+
* only `N` leaves are present.
230+
*
231+
* This is used for pruning out the smaller probabilities.
232+
*
233+
* @param N The number of leaves to keep post pruning.
234+
* @return double
235+
*/
236+
double computeThreshold(const size_t N) const;
237+
227238
/**
228239
* @brief Prune the decision tree of discrete variables.
229240
*

gtsam/discrete/tests/testDecisionTreeFactor.cpp

Lines changed: 37 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -140,11 +140,46 @@ TEST(DecisionTreeFactor, enumerate) {
140140
EXPECT(actual == expected);
141141
}
142142

143+
namespace pruning_fixture {
144+
145+
DiscreteKey A(1, 2), B(2, 2), C(3, 2);
146+
DecisionTreeFactor f(A& B& C, "1 5 3 7 2 6 4 8");
147+
148+
DiscreteKey D(4, 2);
149+
DecisionTreeFactor factor(
150+
D& C & B & A,
151+
"0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 "
152+
"0.0 0.0 0.99995287 1.0 1.0 1.0 1.0");
153+
154+
} // namespace pruning_fixture
155+
156+
/* ************************************************************************* */
157+
// Check if computing the correct threshold works.
158+
TEST(DecisionTreeFactor, ComputeThreshold) {
159+
using namespace pruning_fixture;
160+
161+
// Only keep the leaves with the top 5 values.
162+
double threshold = f.computeThreshold(5);
163+
EXPECT_DOUBLES_EQUAL(4.0, threshold, 1e-9);
164+
165+
// Check for more extreme pruning where we only keep the top 2 leaves
166+
threshold = f.computeThreshold(2);
167+
EXPECT_DOUBLES_EQUAL(7.0, threshold, 1e-9);
168+
169+
threshold = factor.computeThreshold(5);
170+
EXPECT_DOUBLES_EQUAL(0.99995287, threshold, 1e-9);
171+
172+
threshold = factor.computeThreshold(3);
173+
EXPECT_DOUBLES_EQUAL(1.0, threshold, 1e-9);
174+
175+
threshold = factor.computeThreshold(6);
176+
EXPECT_DOUBLES_EQUAL(0.61247742, threshold, 1e-9);
177+
}
178+
143179
/* ************************************************************************* */
144180
// Check pruning of the decision tree works as expected.
145181
TEST(DecisionTreeFactor, Prune) {
146-
DiscreteKey A(1, 2), B(2, 2), C(3, 2);
147-
DecisionTreeFactor f(A & B & C, "1 5 3 7 2 6 4 8");
182+
using namespace pruning_fixture;
148183

149184
// Only keep the leaves with the top 5 values.
150185
size_t maxNrAssignments = 5;
@@ -160,12 +195,6 @@ TEST(DecisionTreeFactor, Prune) {
160195
DecisionTreeFactor expected2(A & B & C, "0 0 0 7 0 0 0 8");
161196
EXPECT(assert_equal(expected2, pruned2));
162197

163-
DiscreteKey D(4, 2);
164-
DecisionTreeFactor factor(
165-
D & C & B & A,
166-
"0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 "
167-
"0.0 0.0 0.99995287 1.0 1.0 1.0 1.0");
168-
169198
DecisionTreeFactor expected3(D & C & B & A,
170199
"0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 "
171200
"0.999952870000 1.0 1.0 1.0 1.0");

gtsam/geometry/geometry.i

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -360,6 +360,7 @@ class Rot3 {
360360
// Standard Interface
361361
static gtsam::Rot3 Expmap(gtsam::Vector v);
362362
static gtsam::Vector Logmap(const gtsam::Rot3& p);
363+
gtsam::Rot3 expmap(const gtsam::Vector& v);
363364
gtsam::Vector logmap(const gtsam::Rot3& p);
364365
gtsam::Matrix matrix() const;
365366
gtsam::Matrix transpose() const;

gtsam/hybrid/HybridBayesTree.cpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -210,9 +210,11 @@ void HybridBayesTree::prune(const size_t maxNrLeaves) {
210210
if (conditional->isHybrid()) {
211211
auto hybridGaussianCond = conditional->asHybrid();
212212

213-
// Imperative
214-
clique->conditional() = std::make_shared<HybridConditional>(
215-
hybridGaussianCond->prune(parentData.prunedDiscreteProbs));
213+
if (!hybridGaussianCond->pruned()) {
214+
// Imperative
215+
clique->conditional() = std::make_shared<HybridConditional>(
216+
hybridGaussianCond->prune(parentData.prunedDiscreteProbs));
217+
}
216218
}
217219
return parentData;
218220
}

gtsam/hybrid/HybridGaussianConditional.cpp

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -120,7 +120,7 @@ struct HybridGaussianConditional::Helper {
120120

121121
/* *******************************************************************************/
122122
HybridGaussianConditional::HybridGaussianConditional(
123-
const DiscreteKeys &discreteParents, Helper &&helper)
123+
const DiscreteKeys &discreteParents, Helper &&helper, bool pruned)
124124
: BaseFactor(discreteParents,
125125
FactorValuePairs(
126126
[&](const GaussianFactorValuePair
@@ -130,7 +130,8 @@ HybridGaussianConditional::HybridGaussianConditional(
130130
},
131131
std::move(helper.pairs))),
132132
BaseConditional(*helper.nrFrontals),
133-
negLogConstant_(helper.minNegLogConstant) {}
133+
negLogConstant_(helper.minNegLogConstant),
134+
pruned_(pruned) {}
134135

135136
HybridGaussianConditional::HybridGaussianConditional(
136137
const DiscreteKey &discreteParent,
@@ -166,8 +167,9 @@ HybridGaussianConditional::HybridGaussianConditional(
166167
: HybridGaussianConditional(discreteParents, Helper(conditionals)) {}
167168

168169
HybridGaussianConditional::HybridGaussianConditional(
169-
const DiscreteKeys &discreteParents, const FactorValuePairs &pairs)
170-
: HybridGaussianConditional(discreteParents, Helper(pairs)) {}
170+
const DiscreteKeys &discreteParents, const FactorValuePairs &pairs,
171+
bool pruned)
172+
: HybridGaussianConditional(discreteParents, Helper(pairs), pruned) {}
171173

172174
/* *******************************************************************************/
173175
const HybridGaussianConditional::Conditionals
@@ -331,7 +333,7 @@ HybridGaussianConditional::shared_ptr HybridGaussianConditional::prune(
331333

332334
FactorValuePairs prunedConditionals = factors().apply(pruner);
333335
return std::make_shared<HybridGaussianConditional>(discreteKeys(),
334-
prunedConditionals);
336+
prunedConditionals, true);
335337
}
336338

337339
/* *******************************************************************************/

0 commit comments

Comments
 (0)