Skip to content

Commit

Permalink
[common] Add AbstractValue::Make overload for default construction (R…
Browse files Browse the repository at this point in the history
…obotLocomotion#15209)

This enables a few small cleanups, but most importantly gives us a function
pointer that we can use as an allocator callback.
  • Loading branch information
jwnimmer-tri authored Jun 22, 2021
1 parent 7a45bbd commit 8c6596f
Show file tree
Hide file tree
Showing 11 changed files with 30 additions and 12 deletions.
2 changes: 1 addition & 1 deletion bindings/pydrake/common/test/value_test_util_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ PYBIND11_MODULE(value_test_util, m) {
AddValueInstantiation<std::vector<CustomType>>(m);

m.def("make_abstract_value_cc_type_unregistered",
[]() { return AbstractValue::Make(UnregisteredType{}); });
[]() { return AbstractValue::Make<UnregisteredType>(); });
}

} // namespace pydrake
Expand Down
5 changes: 5 additions & 0 deletions common/test/value_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -153,6 +153,11 @@ TYPED_TEST(TypedValueTest, Make) {
EXPECT_EQ(42, abstract_value->template get_value<T>());
}

GTEST_TEST(TypedValueTest, MakeDefault) {
EXPECT_EQ(0, AbstractValue::Make<int>()->get_value<int>());
EXPECT_EQ("", AbstractValue::Make<std::string>()->get_value<std::string>());
}

GTEST_TEST(ValueTest, NiceTypeName) {
auto double_value = AbstractValue::Make<double>(3.);
auto string_value = AbstractValue::Make<std::string>("hello");
Expand Down
15 changes: 14 additions & 1 deletion common/value.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,15 @@ class AbstractValue {

virtual ~AbstractValue();

/// Constructs an AbstractValue using T's default constructor, if available.
/// This is only available for T's that support default construction.
#if !defined(DRAKE_DOXYGEN_CXX)
template <typename T,
typename = typename std::enable_if_t<
std::is_default_constructible_v<T>>>
#endif
static std::unique_ptr<AbstractValue> Make();

/// Returns an AbstractValue containing the given @p value.
template <typename T>
static std::unique_ptr<AbstractValue> Make(const T& value);
Expand Down Expand Up @@ -185,7 +194,6 @@ class Value : public AbstractValue {
/// Constructs a Value<T> using T's default constructor, if available.
/// This is only available for T's that support default construction.
#if !defined(DRAKE_DOXYGEN_CXX)
// T1 is template boilerplate; do not specify it at call sites.
template <typename T1 = T,
typename = typename std::enable_if_t<
std::is_default_constructible_v<T1>>>
Expand Down Expand Up @@ -641,6 +649,11 @@ struct ValueTraitsImpl<T, false> {

} // namespace internal

template <typename T, typename>
std::unique_ptr<AbstractValue> AbstractValue::Make() {
return std::unique_ptr<AbstractValue>(new Value<T>());
}

template <typename T>
std::unique_ptr<AbstractValue> AbstractValue::Make(const T& value) {
return std::unique_ptr<AbstractValue>(new Value<T>(value));
Expand Down
2 changes: 1 addition & 1 deletion multibody/fixed_fem/dev/deformable_model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ void DeformableModel<T>::DoDeclareSystemResources(MultibodyPlant<T>* plant) {
/* Declare output ports. */
vertex_positions_port_ = &this->DeclareAbstractOutputPort(
plant, "vertex_positions",
[]() { return AbstractValue::Make(std::vector<VectorX<T>>{}); },
[]() { return AbstractValue::Make<std::vector<VectorX<T>>>(); },
[this](const systems::Context<T>& context, AbstractValue* output) {
std::vector<VectorX<T>>& output_value =
output->get_mutable_value<std::vector<VectorX<T>>>();
Expand Down
2 changes: 1 addition & 1 deletion perception/point_cloud_to_lcm.cc
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ PointCloudToLcm::PointCloudToLcm(std::string frame_name)
DeclareAbstractInputPort("point_cloud", Value<PointCloud>());
DeclareAbstractOutputPort(
"lcmt_point_cloud",
[]() { return AbstractValue::Make<lcmt_point_cloud>({}); },
[]() { return AbstractValue::Make<lcmt_point_cloud>(); },
[this](const systems::Context<double>& context, AbstractValue* value) {
auto& cloud = this->get_input_port().template Eval<PointCloud>(context);
auto& message = value->get_mutable_value<lcmt_point_cloud>();
Expand Down
2 changes: 1 addition & 1 deletion systems/framework/cache.h
Original file line number Diff line number Diff line change
Expand Up @@ -482,7 +482,7 @@ class CacheEntryValue {
// Default constructor can only be used privately to construct an empty
// CacheEntryValue with description "DUMMY" and a meaningless value.
CacheEntryValue()
: description_("DUMMY"), value_(AbstractValue::Make<int>(0)) {}
: description_("DUMMY"), value_(AbstractValue::Make<int>()) {}

// Creates a new cache value with the given human-readable description and
// (optionally) an abstract value that defines the right concrete type for
Expand Down
2 changes: 1 addition & 1 deletion systems/framework/leaf_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -331,7 +331,7 @@ LeafSystem<T>::LeafSystem(SystemScalarConverter converter)
scratch_cache_index_ =
this->DeclareCacheEntry(
"scratch",
[]() { return AbstractValue::Make(Scratch<T>{}); },
[]() { return AbstractValue::Make<Scratch<T>>(); },
[](const ContextBase&, AbstractValue*) { /* do nothing */ },
{this->nothing_ticket()}).cache_index();

Expand Down
4 changes: 2 additions & 2 deletions systems/framework/test/leaf_system_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -456,7 +456,7 @@ class AllThingsDeprecated final : public LeafSystem<double> {
&AllThingsDeprecated::MakeInt,
&AllThingsDeprecated::CalcInt);
DeclareAbstractOutputPort(
[]() { return AbstractValue::Make<int>(0); },
[]() { return AbstractValue::Make<int>(); },
[](const Context<double>&, AbstractValue*) {});
}

Expand Down Expand Up @@ -1836,7 +1836,7 @@ class DefaultFeedthroughSystem : public LeafSystem<double> {
OutputPortIndex AddAbstractOutputPort(
std::optional<std::set<DependencyTicket>> prerequisites_of_calc = {}) {
// Dummies.
auto alloc = []() { return AbstractValue::Make<int>(0); };
auto alloc = []() { return AbstractValue::Make<int>(); };
auto calc = [](const ContextBase&, AbstractValue*) {};
if (prerequisites_of_calc) {
return this->DeclareAbstractOutputPort(
Expand Down
4 changes: 2 additions & 2 deletions systems/framework/test/system_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -614,7 +614,7 @@ class ValueIOTestSystem : public TestSystemBase<T> {
kAbstractValued, 0 /* size */,
&this->DeclareCacheEntry(
"absport",
[]() { return AbstractValue::Make(std::string()); },
[]() { return AbstractValue::Make<std::string>(); },
[this](const ContextBase& context, AbstractValue* output) {
this->CalcStringOutput(context, output);
})));
Expand Down Expand Up @@ -646,7 +646,7 @@ class ValueIOTestSystem : public TestSystemBase<T> {
std::unique_ptr<AbstractValue> DoAllocateInput(
const InputPort<T>& input_port) const override {
if (input_port.get_index() == 0) {
return AbstractValue::Make<std::string>("");
return AbstractValue::Make<std::string>();
} else {
return std::make_unique<Value<BasicVector<T>>>(TestTypedVector<T>{});
}
Expand Down
2 changes: 1 addition & 1 deletion systems/framework/test/vector_system_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ TEST_F(VectorSystemTest, TopologyFailFast) {
DRAKE_EXPECT_NO_THROW(dut.CreateDefaultContext());
dut.DeclareAbstractOutputPort(
kUseDefaultName,
[]() { return AbstractValue::Make<int>(0); }, // Dummies.
[]() { return AbstractValue::Make<int>(); }, // Dummies.
[](const ContextBase&, AbstractValue*) {});
EXPECT_THROW(dut.CreateDefaultContext(), std::exception);
}
Expand Down
2 changes: 1 addition & 1 deletion systems/rendering/render_pose_to_geometry_pose.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ RenderPoseToGeometryPose<T>::RenderPoseToGeometryPose(
this->DeclareVectorInputPort(kUseDefaultName, Input{});
this->DeclareAbstractOutputPort(
kUseDefaultName,
[]() { return Value<Output>{}.Clone(); },
[]() { return AbstractValue::Make<Output>(); },
[this, frame_id](const Context<T>& context, AbstractValue* calculated) {
const Input& input =
this->get_input_port().template Eval<Input>(context);
Expand Down

0 comments on commit 8c6596f

Please sign in to comment.