Skip to content

Commit

Permalink
Merge pull request RobotLocomotion#8590 from sherm1/PR_remove_context…
Browse files Browse the repository at this point in the history
…_dependency_output_ports

Removes context parameter to output port allocator function
  • Loading branch information
sherm1 authored Apr 13, 2018
2 parents 72b0f5b + cbe1070 commit 84bf11e
Show file tree
Hide file tree
Showing 38 changed files with 108 additions and 161 deletions.
10 changes: 4 additions & 6 deletions examples/geometry_world/bouncing_ball_plant.cc
Original file line number Diff line number Diff line change
Expand Up @@ -96,8 +96,7 @@ void BouncingBallPlant<T>::CopyStateToOutput(
}

template <typename T>
FramePoseVector<T> BouncingBallPlant<T>::AllocateFramePoseOutput(
const Context<T>&) const {
FramePoseVector<T> BouncingBallPlant<T>::AllocateFramePoseOutput() const {
FramePoseVector<T> poses(source_id_);
poses.mutable_vector().push_back(Isometry3<T>::Identity());
return poses;
Expand All @@ -115,16 +114,15 @@ void BouncingBallPlant<T>::CalcFramePoseOutput(
}

template <typename T>
FrameIdVector BouncingBallPlant<T>::AllocateFrameIdOutput(
const systems::Context<T>&) const {
FrameIdVector BouncingBallPlant<T>::AllocateFrameIdOutput() const {
return FrameIdVector(source_id_,
std::vector<geometry::FrameId>{ball_frame_id_});
}

template <typename T>
void BouncingBallPlant<T>::CalcFrameIdOutput(const systems::Context<T>& context,
void BouncingBallPlant<T>::CalcFrameIdOutput(const systems::Context<T>&,
FrameIdVector* frame_ids) const {
*frame_ids = AllocateFrameIdOutput(context);
*frame_ids = AllocateFrameIdOutput();
}

// Compute the actual physics.
Expand Down
6 changes: 2 additions & 4 deletions examples/geometry_world/bouncing_ball_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,16 +83,14 @@ class BouncingBallPlant : public systems::LeafSystem<T> {
BouncingBallVector<T>* state_output_vector) const;

// Allocate the frame pose set output port value.
geometry::FramePoseVector<T> AllocateFramePoseOutput(
const systems::Context<T>& context) const;
geometry::FramePoseVector<T> AllocateFramePoseOutput() const;

// Calculate the frame pose set output port value.
void CalcFramePoseOutput(const systems::Context<T>& context,
geometry::FramePoseVector<T>* poses) const;

// Allocate the id output.
geometry::FrameIdVector AllocateFrameIdOutput(
const systems::Context<T>& context) const;
geometry::FrameIdVector AllocateFrameIdOutput() const;

// Calculate the id output.
void CalcFrameIdOutput(const systems::Context<T>& context,
Expand Down
5 changes: 2 additions & 3 deletions examples/geometry_world/solar_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -261,8 +261,7 @@ void SolarSystem<T>::AllocateGeometry(GeometrySystem<T>* geometry_system) {
}

template <typename T>
FramePoseVector<T> SolarSystem<T>::AllocateFramePoseOutput(
const Context<T>&) const {
FramePoseVector<T> SolarSystem<T>::AllocateFramePoseOutput() const {
DRAKE_DEMAND(source_id_.is_valid());
DRAKE_DEMAND(static_cast<int>(body_offset_.size()) == kBodyCount);
// NOTE: We initialize with the translational offset during allocation so that
Expand All @@ -285,7 +284,7 @@ void SolarSystem<T>::CalcFramePoseOutput(const Context<T>& context,
}

template <typename T>
FrameIdVector SolarSystem<T>::AllocateFrameIdOutput(const MyContext&) const {
FrameIdVector SolarSystem<T>::AllocateFrameIdOutput() const {
DRAKE_DEMAND(source_id_.is_valid());
DRAKE_DEMAND(static_cast<int>(body_offset_.size()) == kBodyCount);
FrameIdVector ids(source_id_);
Expand Down
5 changes: 2 additions & 3 deletions examples/geometry_world/solar_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -125,15 +125,14 @@ class SolarSystem : public systems::LeafSystem<T> {
void AllocateGeometry(geometry::GeometrySystem<T>* geometry_system);

// Allocate the frame pose set output port value.
geometry::FramePoseVector<T> AllocateFramePoseOutput(
const MyContext& context) const;
geometry::FramePoseVector<T> AllocateFramePoseOutput() const;

// Calculate the frame pose set output port value.
void CalcFramePoseOutput(const MyContext& context,
geometry::FramePoseVector<T>* poses) const;

// Allocate the id output.
geometry::FrameIdVector AllocateFrameIdOutput(const MyContext& context) const;
geometry::FrameIdVector AllocateFrameIdOutput() const;
// Calculate the id output.
void CalcFrameIdOutput(const MyContext& context,
geometry::FrameIdVector* id_set) const;
Expand Down
3 changes: 1 addition & 2 deletions geometry/geometry_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -209,8 +209,7 @@ void GeometrySystem<T>::MakeSourcePorts(SourceId source_id) {
}

template <typename T>
QueryObject<T> GeometrySystem<T>::MakeQueryObject(
const systems::Context<T>&) const {
QueryObject<T> GeometrySystem<T>::MakeQueryObject() const {
// Returns a null-initialized QueryObject to be compatible with context
// allocation (see documentation on QueryObject).
return QueryObject<T>();
Expand Down
2 changes: 1 addition & 1 deletion geometry/geometry_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -408,7 +408,7 @@ class GeometrySystem final : public systems::LeafSystem<T> {
friend void DispatchLoadMessage(const GeometrySystem<double>&);

// Constructs a QueryObject for OutputPort allocation.
QueryObject<T> MakeQueryObject(const systems::Context<T>& context) const;
QueryObject<T> MakeQueryObject() const;

// Sets the context into the output port value so downstream consumers can
// perform queries.
Expand Down
6 changes: 2 additions & 4 deletions geometry/test/geometry_system_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -385,8 +385,7 @@ class GeometrySourceSystem : public systems::LeafSystem<double> {

private:
// Frame id output allocation and calculation.
FrameIdVector AllocateFrameIdOutput(
const Context<double>& context) const {
FrameIdVector AllocateFrameIdOutput() const {
FrameIdVector ids(source_id_, frame_ids_);
ids.AddFrameIds(extra_frame_ids_);
return ids;
Expand All @@ -395,8 +394,7 @@ class GeometrySourceSystem : public systems::LeafSystem<double> {
void CalcFrameIdOutput(const Context<double> &context,
FrameIdVector *) const {}
// Frame pose output allocation.
FramePoseVector<double> AllocateFramePoseOutput(
const Context<double>& context) const {
FramePoseVector<double> AllocateFramePoseOutput() const {
FramePoseVector<double> poses(source_id_);
for (size_t i = 0; i < frame_ids_.size(); ++i) {
poses.mutable_vector().push_back(Isometry3<double>::Identity());
Expand Down
6 changes: 2 additions & 4 deletions multibody/multibody_tree/multibody_plant/multibody_plant.cc
Original file line number Diff line number Diff line change
Expand Up @@ -534,8 +534,7 @@ void MultibodyPlant<T>::DeclareGeometrySystemPorts() {
}

template <typename T>
FrameIdVector MultibodyPlant<T>::AllocateFrameIdOutput(
const Context<T>&) const {
FrameIdVector MultibodyPlant<T>::AllocateFrameIdOutput() const {
DRAKE_MBP_THROW_IF_NOT_FINALIZED();
DRAKE_DEMAND(source_id_ != nullopt);
// User must be done adding elements to the model.
Expand All @@ -553,8 +552,7 @@ void MultibodyPlant<T>::CalcFrameIdOutput(
}

template <typename T>
FramePoseVector<T> MultibodyPlant<T>::AllocateFramePoseOutput(
const Context<T>&) const {
FramePoseVector<T> MultibodyPlant<T>::AllocateFramePoseOutput() const {
DRAKE_MBP_THROW_IF_NOT_FINALIZED();
DRAKE_DEMAND(source_id_ != nullopt);
FramePoseVector<T> poses(source_id_.value());
Expand Down
6 changes: 2 additions & 4 deletions multibody/multibody_tree/multibody_plant/multibody_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -885,15 +885,13 @@ class MultibodyPlant : public systems::LeafSystem<T> {
// with a GeometrySystem.
void DeclareGeometrySystemPorts();

geometry::FrameIdVector AllocateFrameIdOutput(
const systems::Context<T>& context) const;
geometry::FrameIdVector AllocateFrameIdOutput() const;

void CalcFrameIdOutput(
const systems::Context<T>& context,
geometry::FrameIdVector* id_set) const;

geometry::FramePoseVector<T> AllocateFramePoseOutput(
const systems::Context<T>& context) const;
geometry::FramePoseVector<T> AllocateFramePoseOutput() const;

void CalcFramePoseOutput(const systems::Context<T>& context,
geometry::FramePoseVector<T>* poses) const;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -306,14 +306,14 @@ TEST_F(AcrobotPlantTests, VisualGeometryRegistration) {
plant_->CreateDefaultContext();

std::unique_ptr<AbstractValue> ids_value =
plant_->get_geometry_ids_output_port().Allocate(*context);
plant_->get_geometry_ids_output_port().Allocate();
EXPECT_NO_THROW(ids_value->GetValueOrThrow<FrameIdVector>());
const FrameIdVector& ids = ids_value->GetValueOrThrow<FrameIdVector>();
EXPECT_EQ(ids.get_source_id(), plant_->get_source_id());
EXPECT_EQ(ids.size(), 2); // Only two frames move.

std::unique_ptr<AbstractValue> poses_value =
plant_->get_geometry_poses_output_port().Allocate(*context);
plant_->get_geometry_poses_output_port().Allocate();
EXPECT_NO_THROW(poses_value->GetValueOrThrow<FramePoseVector<double>>());
const FramePoseVector<double>& poses =
poses_value->GetValueOrThrow<FramePoseVector<double>>();
Expand Down Expand Up @@ -399,14 +399,14 @@ GTEST_TEST(MultibodyPlantTest, CollisionGeometryRegistration) {
context.get());

std::unique_ptr<AbstractValue> ids_value =
plant.get_geometry_ids_output_port().Allocate(*context);
plant.get_geometry_ids_output_port().Allocate();
EXPECT_NO_THROW(ids_value->GetValueOrThrow<FrameIdVector>());
const FrameIdVector& ids = ids_value->GetValueOrThrow<FrameIdVector>();
EXPECT_EQ(ids.get_source_id(), plant.get_source_id());
EXPECT_EQ(ids.size(), 2); // Only two frames move.

std::unique_ptr<AbstractValue> poses_value =
plant.get_geometry_poses_output_port().Allocate(*context);
plant.get_geometry_poses_output_port().Allocate();
EXPECT_NO_THROW(poses_value->GetValueOrThrow<FramePoseVector<double>>());
const FramePoseVector<double>& poses =
poses_value->GetValueOrThrow<FramePoseVector<double>>();
Expand Down Expand Up @@ -494,7 +494,7 @@ TEST_F(AcrobotPlantTests, EvalContinuousStateOutputPort) {
elbow_->set_angular_rate(context.get(), 2.5);

std::unique_ptr<AbstractValue> state_value =
plant_->get_continuous_state_output_port().Allocate(*context);
plant_->get_continuous_state_output_port().Allocate();
EXPECT_NO_THROW(state_value->GetValueOrThrow<BasicVector<double>>());
const BasicVector<double>& state_out =
state_value->GetValueOrThrow<BasicVector<double>>();
Expand Down
6 changes: 2 additions & 4 deletions multibody/rigid_body_plant/rigid_body_plant_bridge.cc
Original file line number Diff line number Diff line change
Expand Up @@ -139,8 +139,7 @@ void RigidBodyPlantBridge<T>::RegisterTree(GeometrySystem<T>* geometry_system) {
}

template <typename T>
FramePoseVector<T> RigidBodyPlantBridge<T>::AllocateFramePoseOutput(
const MyContext&) const {
FramePoseVector<T> RigidBodyPlantBridge<T>::AllocateFramePoseOutput() const {
DRAKE_DEMAND(source_id_.is_valid());
// Poses of the registered bodies in the world -- defaults to identity.
std::vector<Isometry3<T>> X_WF(body_ids_.size(), Isometry3<T>::Identity());
Expand Down Expand Up @@ -172,8 +171,7 @@ void RigidBodyPlantBridge<T>::CalcFramePoseOutput(
}

template <typename T>
FrameIdVector RigidBodyPlantBridge<T>::AllocateFrameIdOutput(
const MyContext&) const {
FrameIdVector RigidBodyPlantBridge<T>::AllocateFrameIdOutput() const {
DRAKE_DEMAND(source_id_.is_valid());
FrameIdVector ids(source_id_, body_ids_);
return ids;
Expand Down
5 changes: 2 additions & 3 deletions multibody/rigid_body_plant/rigid_body_plant_bridge.h
Original file line number Diff line number Diff line change
Expand Up @@ -129,15 +129,14 @@ class RigidBodyPlantBridge : public systems::LeafSystem<T> {
}

// Allocate the frame pose set output port value.
geometry::FramePoseVector<T> AllocateFramePoseOutput(
const MyContext& context) const;
geometry::FramePoseVector<T> AllocateFramePoseOutput() const;

// Calculate the frame pose set output port value.
void CalcFramePoseOutput(const MyContext& context,
geometry::FramePoseVector<T>* poses) const;

// Allocate the id output.
geometry::FrameIdVector AllocateFrameIdOutput(const MyContext& context) const;
geometry::FrameIdVector AllocateFrameIdOutput() const;
// Calculate the id output.
void CalcFrameIdOutput(const MyContext& context,
geometry::FrameIdVector* id_set) const;
Expand Down
2 changes: 1 addition & 1 deletion systems/controllers/test/dynamic_programming_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ GTEST_TEST(FittedValueIterationTest, SingleIntegrator) {
// Optimal policy is 1 if x < 0, 0 if x = 0, -1 if x > 0.
EXPECT_EQ(policy->get_output_port().size(), 1);
auto context = policy->CreateDefaultContext();
auto output = policy->get_output_port().Allocate(*context);
auto output = policy->get_output_port().Allocate();
for (const double x : state_grid[0]) {
context->FixInputPort(0, Vector1d{x});
policy->get_output_port().Calc(*context, output.get());
Expand Down
9 changes: 5 additions & 4 deletions systems/framework/cache_entry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -47,17 +47,18 @@ void CacheEntry::Calc(const ContextBase& context,
AbstractValue* value) const {
DRAKE_DEMAND(value != nullptr);
DRAKE_ASSERT_VOID(owning_subsystem_->ThrowIfContextNotCompatible(context));
DRAKE_ASSERT_VOID(CheckValidAbstractValue(context, *value));
DRAKE_ASSERT_VOID(CheckValidAbstractValue(*value));

calc_function_(context, value);
}

void CacheEntry::CheckValidAbstractValue(const ContextBase&,
const AbstractValue& proposed) const {
// See OutputPort::CheckValidOutputType; treat both methods similarly.
void CacheEntry::CheckValidAbstractValue(const AbstractValue& proposed) const {
// TODO(sherm1) Consider whether we can depend on there already being an
// object of this type in the context's CacheEntryValue so we
// wouldn't have to allocate one here. If so could also store
// a precomputed type_index there for further savings.
// a precomputed type_index there for further savings. Would
// need to pass in a ContextBase.
auto good_ptr = Allocate(); // Very expensive!
const AbstractValue& good = *good_ptr;
if (typeid(proposed) != typeid(good)) {
Expand Down
3 changes: 1 addition & 2 deletions systems/framework/cache_entry.h
Original file line number Diff line number Diff line change
Expand Up @@ -289,8 +289,7 @@ class CacheEntry {

// Check that an AbstractValue provided to Calc() is suitable for this cache
// entry. (Very expensive; use in Debug only.)
void CheckValidAbstractValue(const ContextBase& context,
const AbstractValue& proposed) const;
void CheckValidAbstractValue(const AbstractValue& proposed) const;

// Provides an identifying prefix for error messages.
std::string FormatName(const char* api) const;
Expand Down
11 changes: 5 additions & 6 deletions systems/framework/diagram.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,14 +69,13 @@ class DiagramOutputPort : public OutputPort<T> {
}

private:
// These forward to the source system output port, passing in just the source
// System's Context, not the whole Diagram context we're given.
std::unique_ptr<AbstractValue> DoAllocate(
const Context<T>& context) const final {
const Context<T>& subcontext = get_subcontext(context);
return source_output_port_->Allocate(subcontext);
// These forward to the source system output port.
std::unique_ptr<AbstractValue> DoAllocate() const final {
return source_output_port_->Allocate();
}

// Pass in just the source System's Context, not the whole Diagram context
// we're given.
void DoCalc(
const Context<T>& context, AbstractValue* value) const final {
const Context<T>& subcontext = get_subcontext(context);
Expand Down
7 changes: 2 additions & 5 deletions systems/framework/leaf_output_port.cc
Original file line number Diff line number Diff line change
Expand Up @@ -36,14 +36,11 @@ void LeafOutputPort<T>::set_calculation_function(
}

template <typename T>
std::unique_ptr<AbstractValue> LeafOutputPort<T>::DoAllocate(
const Context<T>& context) const {
std::unique_ptr<AbstractValue> LeafOutputPort<T>::DoAllocate() const {
std::unique_ptr<AbstractValue> result;

// Use the allocation function if available, otherwise clone the model
// value.
if (alloc_function_) {
result = alloc_function_(context);
result = alloc_function_();
} else {
throw std::logic_error(
"LeafOutputPort::DoAllocate(): " + this->GetPortIdString() +
Expand Down
6 changes: 2 additions & 4 deletions systems/framework/leaf_output_port.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,7 @@ class LeafOutputPort : public OutputPort<T> {
/** Signature of a function suitable for allocating an object that can hold
a value of a particular output port. The result is returned as an
AbstractValue even if this is a vector-valued port. */
using AllocCallback = std::function<std::unique_ptr<AbstractValue>(
const Context<T>&)>;
using AllocCallback = std::function<std::unique_ptr<AbstractValue>()>;

/** Signature of a function suitable for calculating a value of a particular
output port, given a place to put the value. */
Expand Down Expand Up @@ -129,8 +128,7 @@ class LeafOutputPort : public OutputPort<T> {

// Invokes the supplied allocation function if there is one, otherwise
// complains.
std::unique_ptr<AbstractValue> DoAllocate(
const Context<T>& context) const final;
std::unique_ptr<AbstractValue> DoAllocate() const final;

// Invokes the supplied calculation function if present, otherwise complains.
void DoCalc(const Context<T>& context, AbstractValue* value) const final;
Expand Down
Loading

0 comments on commit 84bf11e

Please sign in to comment.