Skip to content

Commit

Permalink
refactor(tree_structured_parzen_estimator): apply static analysis (au…
Browse files Browse the repository at this point in the history
…towarefoundation#7364)

* refactor based on linter

Signed-off-by: a-maumau <[email protected]>

* fix to match the change in TreeStructuredParzenEstimator

Signed-off-by: a-maumau <[email protected]>

* style(pre-commit): autofix

* apply suggestion

Signed-off-by: a-maumau <[email protected]>

* revert const declare

Signed-off-by: a-maumau <[email protected]>

* revert const declare

Signed-off-by: a-maumau <[email protected]>

---------

Signed-off-by: a-maumau <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: SakodaShintaro <[email protected]>
  • Loading branch information
3 people authored Jun 13, 2024
1 parent 796f72d commit 898fb73
Show file tree
Hide file tree
Showing 3 changed files with 38 additions and 41 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -56,19 +56,20 @@ class TreeStructuredParzenEstimator

TreeStructuredParzenEstimator() = delete;
TreeStructuredParzenEstimator(
const Direction direction, const int64_t n_startup_trials,
const std::vector<double> & sample_mean, const std::vector<double> & sample_stddev);
const Direction direction, const int64_t n_startup_trials, std::vector<double> sample_mean,
std::vector<double> sample_stddev);
void add_trial(const Trial & trial);
Input get_next_input() const;
[[nodiscard]] Input get_next_input() const;

private:
static constexpr double MAX_GOOD_RATE = 0.10;
static constexpr int64_t N_EI_CANDIDATES = 100;
static constexpr double max_good_rate = 0.10;
static constexpr int64_t n_ei_candidates = 100;

static std::mt19937_64 engine;

double compute_log_likelihood_ratio(const Input & input) const;
double log_gaussian_pdf(const Input & input, const Input & mu, const Input & sigma) const;
[[nodiscard]] double compute_log_likelihood_ratio(const Input & input) const;
[[nodiscard]] static double log_gaussian_pdf(
const Input & input, const Input & mu, const Input & sigma);

std::vector<Trial> trials_;
int64_t above_num_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,14 +23,14 @@
std::mt19937_64 TreeStructuredParzenEstimator::engine(std::random_device{}());

TreeStructuredParzenEstimator::TreeStructuredParzenEstimator(
const Direction direction, const int64_t n_startup_trials,
const std::vector<double> & sample_mean, const std::vector<double> & sample_stddev)
const Direction direction, const int64_t n_startup_trials, std::vector<double> sample_mean,
std::vector<double> sample_stddev)
: above_num_(0),
direction_(direction),
n_startup_trials_(n_startup_trials),
input_dimension_(INDEX_NUM),
sample_mean_(sample_mean),
sample_stddev_(sample_stddev)
sample_mean_(std::move(sample_mean)),
sample_stddev_(std::move(sample_stddev))
{
if (sample_mean_.size() != ANGLE_Z) {
std::cerr << "sample_mean size is invalid" << std::endl;
Expand All @@ -56,8 +56,9 @@ void TreeStructuredParzenEstimator::add_trial(const Trial & trial)
std::sort(trials_.begin(), trials_.end(), [this](const Trial & lhs, const Trial & rhs) {
return (direction_ == Direction::MAXIMIZE ? lhs.score > rhs.score : lhs.score < rhs.score);
});
above_num_ =
std::min({static_cast<int64_t>(10), static_cast<int64_t>(trials_.size() * MAX_GOOD_RATE)});
above_num_ = std::min(
{static_cast<int64_t>(10),
static_cast<int64_t>(static_cast<double>(trials_.size()) * max_good_rate)});
}

TreeStructuredParzenEstimator::Input TreeStructuredParzenEstimator::get_next_input() const
Expand Down Expand Up @@ -88,7 +89,7 @@ TreeStructuredParzenEstimator::Input TreeStructuredParzenEstimator::get_next_inp

Input best_input;
double best_log_likelihood_ratio = std::numeric_limits<double>::lowest();
for (int64_t i = 0; i < N_EI_CANDIDATES; i++) {
for (int64_t i = 0; i < n_ei_candidates; i++) {
Input input(input_dimension_);
input[TRANS_X] = dist_normal_trans_x(engine);
input[TRANS_Y] = dist_normal_trans_y(engine);
Expand All @@ -107,7 +108,7 @@ TreeStructuredParzenEstimator::Input TreeStructuredParzenEstimator::get_next_inp

double TreeStructuredParzenEstimator::compute_log_likelihood_ratio(const Input & input) const
{
const int64_t n = trials_.size();
const auto n = static_cast<int64_t>(trials_.size());

// The above KDE and the below KDE are calculated respectively, and the ratio is the criteria to
// select best sample.
Expand All @@ -117,22 +118,21 @@ double TreeStructuredParzenEstimator::compute_log_likelihood_ratio(const Input &
for (int64_t i = 0; i < n; i++) {
const double log_p = log_gaussian_pdf(input, trials_[i].input, base_stddev_);
if (i < above_num_) {
const double w = 1.0 / above_num_;
const double w = 1.0 / static_cast<double>(above_num_);
const double log_w = std::log(w);
above_logs.push_back(log_p + log_w);
} else {
const double w = 1.0 / (n - above_num_);
const double w = 1.0 / static_cast<double>(n - above_num_);
const double log_w = std::log(w);
below_logs.push_back(log_p + log_w);
}
}

auto log_sum_exp = [](const std::vector<double> & log_vec) {
const double max = *std::max_element(log_vec.begin(), log_vec.end());
double sum = 0.0;
for (const double log_v : log_vec) {
sum += std::exp(log_v - max);
}
double sum = std::accumulate(
log_vec.begin(), log_vec.end(), 0.0,
[max](double total, double log_v) { return total + std::exp(log_v - max); });
return max + std::log(sum);
};

Expand All @@ -147,14 +147,14 @@ double TreeStructuredParzenEstimator::compute_log_likelihood_ratio(const Input &
}

double TreeStructuredParzenEstimator::log_gaussian_pdf(
const Input & input, const Input & mu, const Input & sigma) const
const Input & input, const Input & mu, const Input & sigma)
{
const double log_2pi = std::log(2.0 * M_PI);
auto log_gaussian_pdf_1d = [&](const double diff, const double sigma) {
return -0.5 * log_2pi - std::log(sigma) - (diff * diff) / (2.0 * sigma * sigma);
};

const int64_t n = input.size();
const auto n = static_cast<int64_t>(input.size());

double result = 0.0;
for (int64_t i = 0; i < n; i++) {
Expand Down
32 changes: 14 additions & 18 deletions localization/tree_structured_parzen_estimator/test/test_tpe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,34 +20,31 @@ TEST(TreeStructuredParzenEstimatorTest, TPE_is_better_than_random_search_on_sphe
{
auto sphere_function = [](const TreeStructuredParzenEstimator::Input & input) {
double value = 0.0;
const int64_t n = input.size();
const auto n = static_cast<int64_t>(input.size());
for (int64_t i = 0; i < n; i++) {
const double v = input[i] * 10;
value += v * v;
}
return value;
};

constexpr int64_t kOuterTrialsNum = 20;
constexpr int64_t kInnerTrialsNum = 200;
constexpr int64_t k_outer_trials_num = 20;
constexpr int64_t k_inner_trials_num = 200;
std::cout << std::fixed;
std::vector<double> mean_scores;
const int64_t n_startup_trials = kInnerTrialsNum / 10;
const std::string method = ((n_startup_trials == kInnerTrialsNum) ? "Random" : "TPE");
std::vector<double> sample_mean(5, 0.0);
std::vector<double> sample_stddev{1.0, 1.0, 0.1, 0.1, 0.1};

const std::vector<double> sample_mean(5, 0.0);
const std::vector<double> sample_stddev{1.0, 1.0, 0.1, 0.1, 0.1};

for (const int64_t n_startup_trials : {kInnerTrialsNum, kInnerTrialsNum / 2}) {
const std::string method = ((n_startup_trials == kInnerTrialsNum) ? "Random" : "TPE");
for (const int64_t n_startup_trials : {k_inner_trials_num, k_inner_trials_num / 2}) {
const std::string method = ((n_startup_trials == k_inner_trials_num) ? "Random" : "TPE");

std::vector<double> scores;
for (int64_t i = 0; i < kOuterTrialsNum; i++) {
for (int64_t i = 0; i < k_outer_trials_num; i++) {
double best_score = std::numeric_limits<double>::lowest();
TreeStructuredParzenEstimator estimator(
TreeStructuredParzenEstimator::Direction::MAXIMIZE, n_startup_trials, sample_mean,
sample_stddev);
for (int64_t trial = 0; trial < kInnerTrialsNum; trial++) {
for (int64_t trial = 0; trial < k_inner_trials_num; trial++) {
const TreeStructuredParzenEstimator::Input input = estimator.get_next_input();
const double score = -sphere_function(input);
estimator.add_trial({input, score});
Expand All @@ -57,13 +54,12 @@ TEST(TreeStructuredParzenEstimatorTest, TPE_is_better_than_random_search_on_sphe
}

const double sum = std::accumulate(scores.begin(), scores.end(), 0.0);
const double mean = sum / scores.size();
const double mean = sum / static_cast<double>(scores.size());
mean_scores.push_back(mean);
double sq_sum = 0.0;
for (const double score : scores) {
sq_sum += (score - mean) * (score - mean);
}
const double stddev = std::sqrt(sq_sum / scores.size());
double sq_sum = std::accumulate(
scores.begin(), scores.end(), 0.0,
[mean](double total, double score) { return total + (score - mean) * (score - mean); });
const double stddev = std::sqrt(sq_sum / static_cast<double>(scores.size()));

std::cout << method << ", mean = " << mean << ", stddev = " << stddev << std::endl;
}
Expand Down

0 comments on commit 898fb73

Please sign in to comment.