Skip to content

Commit

Permalink
Rename InputPort to InputPortValue (RobotLocomotion#5533)
Browse files Browse the repository at this point in the history
* Rename InputPort to InputPortValue and clarify some comments.

* Rename Context::Set/GetInputPort to Set/GetInputPortValue.
Line length, variable name, and comment fixes.

* Minor name fix.

* Line length fixes.

* Renamed system_input files to input_port_value.

* Realphabetize header file lists.

* Fix odd indentation & sorting.

* Renamed system_output files to corresponding output_port_value files.

* CMake fix.

* Change dangerous version of FixInputPort to be safe with respect to invalidation.
  • Loading branch information
sherm1 authored Mar 21, 2017
1 parent 4d6ef1f commit 341ca0f
Show file tree
Hide file tree
Showing 68 changed files with 475 additions and 438 deletions.
15 changes: 9 additions & 6 deletions drake/automotive/test/simple_car_to_euler_floating_joint_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,9 @@ GTEST_TEST(SimpleCarToEulerFloatingJointTest, BasicTest) {
value->set_x(11.0);
value->set_y(22.0);
value->set_heading(33.0);
context->SetInputPort(
0, std::make_unique<systems::FreestandingInputPort>(std::move(value)));
context->SetInputPortValue(
0,
std::make_unique<systems::FreestandingInputPortValue>(std::move(value)));

// Grab a pointer to where the CalcOutput results end up.
const EulerFloatingJointState<double>* const result =
Expand Down Expand Up @@ -71,8 +72,9 @@ GTEST_TEST(SimpleCarToEulerFloatingJointTest, XOriginOffsetTest) {
value->set_x(kX);
value->set_y(kY);
value->set_heading(kZeroHeading);
context->SetInputPort(
0, std::make_unique<systems::FreestandingInputPort>(std::move(value)));
context->SetInputPortValue(
0, std::make_unique<systems::FreestandingInputPortValue>(
std::move(value)));
}

dut->CalcOutput(*context, output.get());
Expand All @@ -91,8 +93,9 @@ GTEST_TEST(SimpleCarToEulerFloatingJointTest, XOriginOffsetTest) {
value->set_x(kX);
value->set_y(kY);
value->set_heading(kLeftHeading);
context->SetInputPort(
0, std::make_unique<systems::FreestandingInputPort>(std::move(value)));
context->SetInputPortValue(
0, std::make_unique<systems::FreestandingInputPortValue>(
std::move(value)));
}

dut->CalcOutput(*context, output.get());
Expand Down
8 changes: 4 additions & 4 deletions drake/examples/Acrobot/test/acrobot_urdf_dynamics_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@ GTEST_TEST(UrdfDynamicsTest, AllTests) {
auto context_rbp = rbp.CreateDefaultContext();
auto context_p = p.CreateDefaultContext();

auto u_rbp = context_rbp->FixInputPort(0, Vector1d::Zero());
auto u_p = context_p->FixInputPort(0, Vector1d::Zero());
auto& u_rbp = context_rbp->FixInputPort(0, Vector1d::Zero());
auto& u_p = context_p->FixInputPort(0, Vector1d::Zero());

Eigen::Vector4d x;
Vector1d u;
Expand All @@ -46,8 +46,8 @@ GTEST_TEST(UrdfDynamicsTest, AllTests) {
context_rbp->get_mutable_continuous_state_vector()->SetFromVector(x);
context_p->get_mutable_continuous_state_vector()->SetFromVector(x);

u_rbp->SetFromVector(u);
u_p->SetFromVector(u);
u_rbp.GetMutableVectorData<double>()->SetFromVector(u);
u_p.GetMutableVectorData<double>()->SetFromVector(u);

rbp.CalcTimeDerivatives(*context_rbp, xdot_rbp.get());
p.CalcTimeDerivatives(*context_p, xdot_p.get());
Expand Down
2 changes: 1 addition & 1 deletion drake/examples/Pendulum/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ drake_cc_binary(
data = [":models"],
test_rule_args = ["--target_realtime_rate=0.0"],
deps = [
"@gflags//:gflags",
"pendulum_swing_up",
"//drake/common:drake_path",
"//drake/common:is_approx_equal_abstol",
Expand All @@ -108,7 +109,6 @@ drake_cc_binary(
"//drake/systems/framework",
"//drake/systems/primitives:trajectory_source",
"//drake/systems/trajectory_optimization:direct_collocation",
"@gflags//:gflags",
],
)

Expand Down
2 changes: 1 addition & 1 deletion drake/examples/Pendulum/pendulum_run_lqr.cc
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@
#include "drake/systems/framework/basic_vector.h"
#include "drake/systems/framework/diagram.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/framework/input_port_value.h"
#include "drake/systems/framework/leaf_system.h"
#include "drake/systems/framework/system_input.h"

namespace drake {
namespace examples {
Expand Down
8 changes: 4 additions & 4 deletions drake/examples/Pendulum/test/pendulum_urdf_dynamics_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@ GTEST_TEST(UrdfDynamicsTest, AllTests) {
auto context_rbp = rbp.CreateDefaultContext();
auto context_p = p.CreateDefaultContext();

auto u_rbp = context_rbp->FixInputPort(0, Vector1d::Zero());
auto u_p = context_p->FixInputPort(0, Vector1d::Zero());
auto& u_rbp = context_rbp->FixInputPort(0, Vector1d::Zero());
auto& u_p = context_p->FixInputPort(0, Vector1d::Zero());

Eigen::Vector2d x;
Vector1d u;
Expand All @@ -41,8 +41,8 @@ GTEST_TEST(UrdfDynamicsTest, AllTests) {
context_rbp->get_mutable_continuous_state_vector()->SetFromVector(x);
context_p->get_mutable_continuous_state_vector()->SetFromVector(x);

u_rbp->SetFromVector(u);
u_p->SetFromVector(u);
u_rbp.GetMutableVectorData<double>()->SetFromVector(u);
u_p.GetMutableVectorData<double>()->SetFromVector(u);

rbp.CalcTimeDerivatives(*context_rbp, xdot_rbp.get());
p.CalcTimeDerivatives(*context_p, xdot_p.get());
Expand Down
10 changes: 5 additions & 5 deletions drake/examples/schunk_wsg/test/schunk_wsg_lcm_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@

#include "drake/lcmt_schunk_wsg_command.hpp"
#include "drake/systems/analysis/simulator.h"
#include "drake/systems/framework/system_input.h"
#include "drake/systems/framework/system_output.h"
#include "drake/systems/framework/input_port_value.h"
#include "drake/systems/framework/output_port_value.h"

namespace drake {
namespace examples {
Expand All @@ -26,11 +26,11 @@ GTEST_TEST(SchunkWsgLcmTest, SchunkWsgTrajectoryGeneratorTest) {
lcmt_schunk_wsg_command initial_command{};
initial_command.target_position_mm = 100;
initial_command.force = 40;
std::unique_ptr<systems::FreestandingInputPort> input_command =
std::make_unique<systems::FreestandingInputPort>(
std::unique_ptr<systems::FreestandingInputPortValue> input_command =
std::make_unique<systems::FreestandingInputPortValue>(
std::make_unique<systems::Value<lcmt_schunk_wsg_command>>(
initial_command));
context->SetInputPort(0, std::move(input_command));
context->SetInputPortValue(0, std::move(input_command));
context->FixInputPort(1, Eigen::VectorXd::Zero(1));

// Step a little bit. We should be commanding a point on the
Expand Down
2 changes: 1 addition & 1 deletion drake/multibody/rigid_body_plant/drake_visualizer.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
#include "drake/multibody/rigid_body_tree.h"
#include "drake/systems/framework/context.h"
#include "drake/systems/framework/leaf_system.h"
#include "drake/systems/framework/system_output.h"
#include "drake/systems/framework/output_port_value.h"
#include "drake/systems/primitives/signal_log.h"

namespace drake {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -478,8 +478,9 @@ GTEST_TEST(DrakeVisualizerTests, BasicTest) {
auto input_data = make_unique<BasicVector<double>>(vector_size);
input_data->set_value(Eigen::VectorXd::Zero(vector_size));

context->SetInputPort(0,
std::make_unique<systems::FreestandingInputPort>(std::move(input_data)));
context->SetInputPortValue(
0, std::make_unique<systems::FreestandingInputPortValue>(
std::move(input_data)));

// Publishes the `RigidBodyTree` visualization messages.
dut.Publish(*context.get());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#include "drake/multibody/parsers/urdf_parser.h"
#include "drake/multibody/rigid_body_tree.h"
#include "drake/systems/framework/basic_vector.h"
#include "drake/systems/framework/system_input.h"
#include "drake/systems/framework/input_port_value.h"

namespace drake {
namespace systems {
Expand Down
2 changes: 1 addition & 1 deletion drake/systems/controllers/test/inverse_dynamics_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#include "drake/multibody/parsers/urdf_parser.h"
#include "drake/multibody/rigid_body_tree.h"
#include "drake/systems/framework/basic_vector.h"
#include "drake/systems/framework/system_input.h"
#include "drake/systems/framework/input_port_value.h"

using Eigen::AutoDiffScalar;
using Eigen::VectorXd;
Expand Down
2 changes: 1 addition & 1 deletion drake/systems/controllers/test/pid_controller_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

#include "drake/common/eigen_types.h"
#include "drake/systems/framework/basic_vector.h"
#include "drake/systems/framework/system_input.h"
#include "drake/systems/framework/input_port_value.h"

using std::make_unique;

Expand Down
24 changes: 12 additions & 12 deletions drake/systems/framework/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -162,9 +162,9 @@ drake_cc_library(
)

drake_cc_library(
name = "system_output",
srcs = ["system_output.cc"],
hdrs = ["system_output.h"],
name = "output_port_value",
srcs = ["output_port_value.cc"],
hdrs = ["output_port_value.h"],
deps = [
":output_port_listener_interface",
":value",
Expand All @@ -179,16 +179,16 @@ drake_cc_library(
srcs = ["input_port_evaluator_interface.cc"],
hdrs = ["input_port_evaluator_interface.h"],
deps = [
":system_output",
":output_port_value",
":system_port_descriptor",
"//drake/common",
],
)

drake_cc_library(
name = "system_input",
srcs = ["system_input.cc"],
hdrs = ["system_input.h"],
name = "input_port_value",
srcs = ["input_port_value.cc"],
hdrs = ["input_port_value.h"],
deps = [
":input_port_evaluator_interface",
":vector",
Expand All @@ -202,9 +202,9 @@ drake_cc_library(
hdrs = ["context.h"],
deps = [
":input_port_evaluator_interface",
":input_port_value",
":parameters",
":state",
":system_input",
"//drake/common",
],
)
Expand Down Expand Up @@ -480,17 +480,17 @@ drake_cc_googletest(
)

drake_cc_googletest(
name = "system_input_test",
name = "input_port_value_test",
deps = [
":system_input",
":input_port_value",
"//drake/common",
],
)

drake_cc_googletest(
name = "system_output_test",
name = "output_port_value_test",
deps = [
":system_output",
":output_port_value",
"//drake/common",
],
)
Expand Down
12 changes: 6 additions & 6 deletions drake/systems/framework/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# Source files used to build drakeSystemFramework.
set(sources
abstract_values.cc
abstract_values.cc
basic_vector.cc
cache.cc
context.cc
Expand All @@ -11,10 +11,12 @@ set(sources
diagram_continuous_state.cc
discrete_state.cc
input_port_evaluator_interface.cc
input_port_value.cc
leaf_context.cc
leaf_system.cc
model_values.cc
output_port_listener_interface.cc
output_port_value.cc
parameters.cc
single_output_vector_source.cc
siso_vector_system.cc
Expand All @@ -23,8 +25,6 @@ set(sources
subvector.cc
supervector.cc
system.cc
system_input.cc
system_output.cc
system_port_descriptor.cc
value.cc
vector_base.cc
Expand All @@ -40,7 +40,7 @@ set(sources
# System2 framework template implementations have been moved into .cc files
# using explicit instantiation, tighten this list.
set(installed_headers
abstract_values.h
abstract_values.h
basic_vector.h
cache.h
context.h
Expand All @@ -51,10 +51,12 @@ set(installed_headers
diagram_continuous_state.h
discrete_state.h
input_port_evaluator_interface.h
input_port_value.h
leaf_context.h
leaf_system.h
model_values.h
output_port_listener_interface.h
output_port_value.h
parameters.h
single_output_vector_source.h
siso_vector_system.h
Expand All @@ -63,8 +65,6 @@ set(installed_headers
subvector.h
supervector.h
system.h
system_input.h
system_output.h
system_port_descriptor.h
systems.h
value.h
Expand Down
Loading

0 comments on commit 341ca0f

Please sign in to comment.