Skip to content

Commit

Permalink
systems/controllers: Change context.FixInputPort() to port.FixValue()
Browse files Browse the repository at this point in the history
  • Loading branch information
mpetersen94 committed Jan 6, 2020
1 parent bc83ee2 commit 87da133
Show file tree
Hide file tree
Showing 6 changed files with 36 additions and 47 deletions.
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 @@ -54,7 +54,7 @@ GTEST_TEST(FittedValueIterationTest, SingleIntegrator) {
auto context = policy->CreateDefaultContext();
auto output = policy->get_output_port().Allocate();
for (const double x : state_grid[0]) {
context->FixInputPort(0, Vector1d{x});
policy->get_input_port().FixValue(context.get(), x);
policy->get_output_port().Calc(*context, output.get());
double y = output->get_value<BasicVector<double>>()[0];
EXPECT_EQ(y, (x < 0) - (x > 0)); // implements -sgn(x).
Expand Down
38 changes: 17 additions & 21 deletions systems/controllers/test/inverse_dynamics_controller_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,27 +51,23 @@ GTEST_TEST(InverseDynamicsControllerTest, TestTorque) {
vd_r << 1, 2, 3, 4, 5, 6, 7;

// Connects inputs.
auto state_input = std::make_unique<BasicVector<double>>(
robot_plant.num_positions() + robot_plant.num_velocities());
state_input->get_mutable_value() << q, v;

auto reference_state_input = std::make_unique<BasicVector<double>>(
robot_plant.num_positions() + robot_plant.num_velocities());
reference_state_input->get_mutable_value() << q_r, v_r;

auto reference_acceleration_input =
std::make_unique<BasicVector<double>>(robot_plant.num_velocities());
reference_acceleration_input->get_mutable_value() << vd_r;

inverse_dynamics_context->FixInputPort(
dut->get_input_port_estimated_state().get_index(),
std::move(state_input));
inverse_dynamics_context->FixInputPort(
dut->get_input_port_desired_state().get_index(),
std::move(reference_state_input));
inverse_dynamics_context->FixInputPort(
dut->get_input_port_desired_acceleration().get_index(),
std::move(reference_acceleration_input));
VectorX<double> state_input(robot_plant.num_positions() +
robot_plant.num_velocities());
state_input << q, v;

VectorX<double> reference_state_input(robot_plant.num_positions() +
robot_plant.num_velocities());
reference_state_input << q_r, v_r;

VectorX<double> reference_acceleration_input(robot_plant.num_velocities());
reference_acceleration_input << vd_r;

dut->get_input_port_estimated_state().FixValue(inverse_dynamics_context.get(),
state_input);
dut->get_input_port_desired_state().FixValue(inverse_dynamics_context.get(),
reference_state_input);
dut->get_input_port_desired_acceleration().FixValue(
inverse_dynamics_context.get(), reference_acceleration_input);

// Sets integrated position error.
VectorX<double> q_int(dim);
Expand Down
18 changes: 6 additions & 12 deletions systems/controllers/test/inverse_dynamics_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -76,20 +76,14 @@ class InverseDynamicsTest : public ::testing::Test {
vd_d = acceleration_desired;
}

auto state_input = make_unique<BasicVector<double>>(
num_positions() + num_velocities());
state_input->get_mutable_value() << position, velocity;
inverse_dynamics_context_->FixInputPort(
inverse_dynamics_->get_input_port_estimated_state().get_index(),
std::move(state_input));
VectorXd state_input(num_positions() + num_velocities());
state_input << position, velocity;
inverse_dynamics_->get_input_port_estimated_state().FixValue(
inverse_dynamics_context_.get(), state_input);

if (!inverse_dynamics_->is_pure_gravity_compensation()) {
auto vd_input =
make_unique<BasicVector<double>>(num_velocities());
vd_input->get_mutable_value() << vd_d;
inverse_dynamics_context_->FixInputPort(
inverse_dynamics_->get_input_port_desired_acceleration().get_index(),
std::move(vd_input));
inverse_dynamics_->get_input_port_desired_acceleration().FixValue(
inverse_dynamics_context_.get(), vd_d);
}

// Hook input of the expected size.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class TestMpcWithDoubleIntegrator : public ::testing::Test {

std::unique_ptr<Context<double>> system_context =
system->CreateDefaultContext();
system_context->FixInputPort(0, u0);
system->get_input_port().FixValue(system_context.get(), u0);
system_context->get_mutable_discrete_state(0).SetFromVector(x0);

dut_.reset(new LinearModelPredictiveController<double>(
Expand Down Expand Up @@ -72,7 +72,7 @@ TEST_F(TestMpcWithDoubleIntegrator, TestAgainstInfiniteHorizonSolution) {
const Eigen::Matrix<double, 2, 1> x0 = Eigen::Vector2d::Ones();

auto context = dut_->CreateDefaultContext();
context->FixInputPort(0, BasicVector<double>::Make(x0(0), x0(1)));
dut_->get_input_port(0).FixValue(context.get(), x0);
std::unique_ptr<SystemOutput<double>> output = dut_->AllocateOutput();

dut_->CalcOutput(*context, output.get());
Expand Down Expand Up @@ -144,7 +144,7 @@ class TestMpcWithCubicSystem : public ::testing::Test {
auto context = system_->CreateDefaultContext();

// Set nominal input to zero.
context->FixInputPort(0, Vector1d::Constant(0.));
system_->get_input_port(0).FixValue(context.get(), 0.);

// Set the nominal state.
BasicVector<double>& x =
Expand Down Expand Up @@ -239,7 +239,7 @@ GTEST_TEST(TestMpcConstructor, ThrowIfRNotStrictlyPositiveDefinite) {
std::make_unique<LinearSystem<double>>(A, B, C, D, 1.);

std::unique_ptr<Context<double>> context = system->CreateDefaultContext();
context->FixInputPort(0, BasicVector<double>::Make(0., 0.));
system->get_input_port().FixValue(context.get(), Eigen::Vector2d::Zero());

const Eigen::Matrix2d Q = Eigen::Matrix2d::Identity();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ void TestLQRAffineSystemAgainstKnownSolution(
Eigen::VectorXd x0 = Eigen::VectorXd::Zero(n);
Eigen::VectorXd u0 = Eigen::VectorXd::Zero(m);

context->FixInputPort(0, u0);
sys.get_input_port().FixValue(context.get(), u0);
if (sys.time_period() == 0.0) {
context->get_mutable_continuous_state().SetFromVector(x0);
} else {
Expand Down
15 changes: 7 additions & 8 deletions systems/controllers/test/pid_controller_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,14 +28,13 @@ class PidControllerTest : public ::testing::Test {
derivatives_ = controller_.AllocateTimeDerivatives();

// State:
auto vec0 = std::make_unique<BasicVector<double>>(port_size_ * 2);
vec0->get_mutable_value().setZero();
context_->FixInputPort(0, std::move(vec0));
VectorX<double> vec0 = VectorX<double>::Zero(port_size_ * 2);
controller_.get_input_port(0).FixValue(context_.get(), vec0);

// Desired state:
auto vec1 = std::make_unique<BasicVector<double>>(port_size_ * 2);
vec1->get_mutable_value() << error_signal_, error_rate_signal_;
context_->FixInputPort(1, std::move(vec1));
VectorX<double> vec1(port_size_ * 2);
vec1 << error_signal_, error_rate_signal_;
controller_.get_input_port(1).FixValue(context_.get(), vec1);
}

const int port_size_{3};
Expand Down Expand Up @@ -224,9 +223,9 @@ GTEST_TEST(PidIOProjectionTest, Test) {
VectorX<double> integral = VectorX<double>::Random(num_controlled_q);

// State:
context->FixInputPort(0, std::make_unique<BasicVector<double>>(x));
dut.get_input_port(0).FixValue(context.get(), x);
// Desired state:
context->FixInputPort(1, std::make_unique<BasicVector<double>>(x_d));
dut.get_input_port(1).FixValue(context.get(), x_d);
// Integral:
dut.set_integral_value(context.get(), integral);

Expand Down

0 comments on commit 87da133

Please sign in to comment.