Skip to content

Commit

Permalink
Allow using Binding<C> as key in unordered_map. (#13322)
Browse files Browse the repository at this point in the history
Allow using Binding<C> as key in unordered_map.
Add operator==, operator!= and hash function for Binding<C>
  • Loading branch information
hongkai-dai authored May 19, 2020
1 parent 5288628 commit c80fb53
Show file tree
Hide file tree
Showing 3 changed files with 134 additions and 27 deletions.
2 changes: 2 additions & 0 deletions solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ drake_cc_library(
hdrs = ["binding.h"],
deps = [
":decision_variable",
":evaluator_base",
],
)

Expand Down Expand Up @@ -1014,6 +1015,7 @@ drake_cc_googletest(
":binding",
":constraint",
":cost",
"//common/test_utilities:eigen_matrix_compare",
"//common/test_utilities:symbolic_test_util",
],
)
Expand Down
46 changes: 46 additions & 0 deletions solvers/binding.h
Original file line number Diff line number Diff line change
@@ -1,13 +1,16 @@
#pragma once

#include <cstdint>
#include <memory>
#include <ostream>
#include <sstream>
#include <string>
#include <utility>

#include "drake/common/drake_copyable.h"
#include "drake/common/hash.h"
#include "drake/solvers/decision_variable.h"
#include "drake/solvers/evaluator_base.h"

namespace drake {
namespace solvers {
Expand Down Expand Up @@ -75,6 +78,44 @@ class Binding {
return os.str();
}

/**
* Compare two bindings based on their evaluator pointers and the bound
* variables.
*/
bool operator==(const Binding<C>& other) const {
if (this->evaluator().get() != other.evaluator().get()) {
return false;
}
DRAKE_DEMAND(vars_.rows() == other.vars_.rows());
for (int i = 0; i < vars_.rows(); ++i) {
if (!vars_(i).equal_to(other.vars_(i))) {
return false;
}
}
return true;
}

bool operator!=(const Binding<C>& other) const {
return !((*this) == (other));
}

/** Implements the @ref hash_append concept. */
template <class HashAlgorithm>
friend void hash_append(HashAlgorithm& hasher,
const Binding<C>& item) noexcept {
using drake::hash_append;
const EvaluatorBase* const base = item.evaluator().get();
hash_append(hasher, reinterpret_cast<std::uintptr_t>(base));
// We follow the pattern in
// http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2014/n3980.html#hash_append_vector
// to append the hash for a std::vector, first to append all its elements,
// and then append the vector size.
for (int i = 0; i < item.variables().rows(); ++i) {
hash_append(hasher, item.variables()(i));
}
hash_append(hasher, item.variables().rows());
}

private:
std::shared_ptr<C> evaluator_;
VectorXDecisionVariable vars_;
Expand Down Expand Up @@ -112,3 +153,8 @@ Binding<To> BindingDynamicCast(const Binding<From>& binding) {

} // namespace solvers
} // namespace drake

namespace std {
template <typename C>
struct hash<drake::solvers::Binding<C>> : public drake::DefaultHash {};
} // namespace std
113 changes: 86 additions & 27 deletions solvers/test/binding_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include <gtest/gtest.h>

#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/common/test_utilities/symbolic_test_util.h"
#include "drake/common/text_logging.h"
#include "drake/solvers/constraint.h"
Expand All @@ -13,43 +14,62 @@ namespace test {

using drake::symbolic::test::VarEqual;

GTEST_TEST(TestBinding, TestConstraint) {
const symbolic::Variable x1("x1");
const symbolic::Variable x2("x2");
const symbolic::Variable x3("x3");
auto bb_con = std::make_shared<BoundingBoxConstraint>(
class TestBinding : public ::testing::Test {
public:
TestBinding() {}

protected:
const symbolic::Variable x1_{"x1"};
const symbolic::Variable x2_{"x2"};
const symbolic::Variable x3_{"x3"};
};

TEST_F(TestBinding, TestConstraintConstruction) {
auto bb_con1 = std::make_shared<BoundingBoxConstraint>(
Eigen::Vector3d::Zero(), Eigen::Vector3d::Ones());

// Checks if the bound variables are stored in the right order.
Binding<BoundingBoxConstraint> binding1(
bb_con,
{VectorDecisionVariable<2>(x3, x1), VectorDecisionVariable<1>(x2)});
bb_con1,
{VectorDecisionVariable<2>(x3_, x1_), VectorDecisionVariable<1>(x2_)});
EXPECT_EQ(binding1.GetNumElements(), 3u);
VectorDecisionVariable<3> var1_expected(x3, x1, x2);
VectorDecisionVariable<3> var1_expected(x3_, x1_, x2_);
for (int i = 0; i < 3; ++i) {
EXPECT_PRED2(VarEqual, binding1.variables()(i), var1_expected(i));
}
bb_con->set_description("dummy bb");
const std::string str_expected1 =
"BoundingBoxConstraint described as 'dummy bb'\n0 <= x3 <= 1\n0 <= x1 <= "
"1\n0 <= x2 <= 1\n";
EXPECT_EQ(fmt::format("{}", binding1), str_expected1);

// Creates a binding with a single VectorDecisionVariable.
Binding<BoundingBoxConstraint> binding2(
bb_con, VectorDecisionVariable<3>(x3, x1, x2));
bb_con1, VectorDecisionVariable<3>(x3_, x1_, x2_));
EXPECT_EQ(binding2.GetNumElements(), 3u);
for (int i = 0; i < 3; ++i) {
EXPECT_PRED2(VarEqual, binding2.variables()(i), var1_expected(i));
}
}

TEST_F(TestBinding, TestPrinting) {
auto bb_con1 = std::make_shared<BoundingBoxConstraint>(
Eigen::Vector3d::Zero(), Eigen::Vector3d::Ones());

// Checks if the bound variables are stored in the right order.
Binding<BoundingBoxConstraint> binding1(
bb_con1,
{VectorDecisionVariable<2>(x3_, x1_), VectorDecisionVariable<1>(x2_)});
bb_con1->set_description("dummy bb");
const std::string str_expected1 =
"BoundingBoxConstraint described as 'dummy bb'\n"
"0 <= x3 <= 1\n"
"0 <= x1 <= 1\n"
"0 <= x2 <= 1\n";
EXPECT_EQ(fmt::format("{}", binding1), str_expected1);

// Test to_string() for LinearEqualityConstraint binding.
Eigen::Matrix2d Aeq;
Aeq << 1, 2, 3, 4;
auto linear_eq_constraint =
std::make_shared<LinearEqualityConstraint>(Aeq, Eigen::Vector2d(1, 2));
Binding<LinearEqualityConstraint> linear_eq_binding(
linear_eq_constraint, VectorDecisionVariable<2>(x1, x2));
linear_eq_constraint, VectorDecisionVariable<2>(x1_, x2_));
const std::string str_expected2 =
"LinearEqualityConstraint\n(x1 + 2 * x2) == 1\n(3 * x1 + 4 * x2) == 2\n";
EXPECT_EQ(fmt::format("{}", linear_eq_binding), str_expected2);
Expand All @@ -58,21 +78,63 @@ GTEST_TEST(TestBinding, TestConstraint) {
const Eigen::Matrix2d Ain = Aeq;
auto linear_ineq_constraint = std::make_shared<LinearConstraint>(
Ain, Eigen::Vector2d(1, 2), Eigen::Vector2d(2, 3));
Binding<LinearConstraint> linear_binding(linear_ineq_constraint,
Vector2<symbolic::Variable>(x1, x2));
Binding<LinearConstraint> linear_binding(
linear_ineq_constraint, Vector2<symbolic::Variable>(x1_, x2_));
const std::string str_expected3 =
"LinearConstraint\n1 <= (x1 + 2 * x2) <= 2\n2 <= (3 * x1 + 4 * x2) <= "
"3\n";
EXPECT_EQ(fmt::format("{}", linear_binding), str_expected3);
EXPECT_EQ(linear_binding.to_string(), str_expected3);
}

GTEST_TEST(TestBinding, TestCost) {
TEST_F(TestBinding, TestHash) {
auto bb_con1 = std::make_shared<BoundingBoxConstraint>(
Eigen::Vector3d::Zero(), Eigen::Vector3d::Ones());

Binding<BoundingBoxConstraint> binding1(
bb_con1,
{VectorDecisionVariable<2>(x3_, x1_), VectorDecisionVariable<1>(x2_)});
EXPECT_EQ(binding1, binding1);

// Creates a binding with a single VectorDecisionVariable.
Binding<BoundingBoxConstraint> binding2(
bb_con1, VectorDecisionVariable<3>(x3_, x1_, x2_));
EXPECT_EQ(binding1, binding2);
// Cast both binding1 and binding2 to Binding<LinearConstraint>. They should
// be equal after casting.
const Binding<LinearConstraint> binding1_cast =
internal::BindingDynamicCast<LinearConstraint>(binding1);
const Binding<LinearConstraint> binding2_cast =
internal::BindingDynamicCast<LinearConstraint>(binding2);
EXPECT_EQ(binding1_cast, binding2_cast);
// binding3 has different variables.
Binding<BoundingBoxConstraint> binding3(
bb_con1, VectorDecisionVariable<3>(x3_, x2_, x1_));
EXPECT_NE(binding1, binding3);
// bb_con2 has different address from bb_con1, although they have the same
// bounds.
auto bb_con2 = std::make_shared<BoundingBoxConstraint>(
Eigen::Vector3d::Zero(), Eigen::Vector3d::Ones());
EXPECT_TRUE(CompareMatrices(bb_con2->lower_bound(), bb_con1->lower_bound()));
EXPECT_TRUE(CompareMatrices(bb_con2->upper_bound(), bb_con1->upper_bound()));
Binding<BoundingBoxConstraint> binding4(
bb_con2, VectorDecisionVariable<3>(x3_, x1_, x2_));
EXPECT_NE(binding4, binding1);
EXPECT_NE(binding4, binding2);

// Test using Binding as unordered_map key.
std::unordered_map<Binding<BoundingBoxConstraint>, int> map;
map.emplace(binding1, 1);
EXPECT_EQ(map.at(binding1), 1);
EXPECT_EQ(map.at(binding2), 1);
EXPECT_EQ(map.find(binding3), map.end());
map.emplace(binding3, 3);
EXPECT_EQ(map.at(binding3), 3);
}

TEST_F(TestBinding, TestCost) {
// Tests binding with a cost.
const symbolic::Variable x1("x1");
const symbolic::Variable x2("x2");
const symbolic::Variable x3("x3");
const VectorDecisionVariable<3> x(x1, x2, x3);
const VectorDecisionVariable<3> x(x1_, x2_, x3_);
// Test a linear cost binding.
auto cost1 = std::make_shared<LinearCost>(Eigen::Vector3d(1, 2, 3), 1);
Binding<LinearCost> binding1(cost1, x);
Expand Down Expand Up @@ -123,12 +185,9 @@ class DummyEvaluator : public EvaluatorBase {
}
};

GTEST_TEST(TestBinding, TestEvaluator) {
TEST_F(TestBinding, TestEvaluator) {
// Tests binding with an evaluator.
const symbolic::Variable x1("x1");
const symbolic::Variable x2("x2");
const symbolic::Variable x3("x3");
const VectorDecisionVariable<3> x(x1, x2, x3);
const VectorDecisionVariable<3> x(x1_, x2_, x3_);
const auto evaluator = std::make_shared<DummyEvaluator>();
evaluator->set_description("dummy");
Binding<DummyEvaluator> binding(evaluator, x);
Expand Down

0 comments on commit c80fb53

Please sign in to comment.