Skip to content

Commit

Permalink
examples: Change context.FixInputPort() to port.FixValue() (RobotLoco…
Browse files Browse the repository at this point in the history
  • Loading branch information
mpetersen94 authored and jwnimmer-tri committed Dec 16, 2019
1 parent 6c2b400 commit 9056a68
Show file tree
Hide file tree
Showing 20 changed files with 119 additions and 199 deletions.
10 changes: 4 additions & 6 deletions examples/allegro_hand/test/allegro_lcm_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,7 @@ GTEST_TEST(AllegroLcmTest, AllegroCommandReceiver) {
command.joint_position[i] = position(i) + delta(i);
}

context->FixInputPort(
0, std::make_unique<Value<lcmt_allegro_command>>(command));
dut.get_input_port(0).FixValue(context.get(), command);

std::unique_ptr<systems::DiscreteValues<double>> update =
dut.AllocateDiscreteVariables();
Expand Down Expand Up @@ -92,19 +91,18 @@ GTEST_TEST(AllegroLcmTest, AllegroStatusSenderTest) {

Eigen::VectorXd command = Eigen::VectorXd::Zero(kAllegroNumJoints * 2);
command.head(kAllegroNumJoints) = position * 0.5;
context->FixInputPort(dut.get_command_input_port().get_index(), command);
dut.get_command_input_port().FixValue(context.get(), command);

Eigen::VectorXd state = Eigen::VectorXd::Zero(kAllegroNumJoints * 2);
state.head(kAllegroNumJoints) = position;
state.tail(kAllegroNumJoints) << 1.6, 1.5, 1.4, 1.3, 1.2, 1.1, 1.0, 0.9, 0.8,
0.7, 0.6, 0.5, 0.4, 0.3, 0.2, 0.1;
context->FixInputPort(dut.get_state_input_port().get_index(), state);
dut.get_state_input_port().FixValue(context.get(), state);

Eigen::VectorXd torque = Eigen::VectorXd::Zero(kAllegroNumJoints);
torque << 1.1, 1.2, 1.3, 1.4, 1.5, 1.6, 1.7, 1.8, 1.9, 2.0, 2.1,
2.2, 2.3, 2.4, 2.5, 2.6;;
context->FixInputPort(
dut.get_commanded_torque_input_port().get_index(), torque);
dut.get_commanded_torque_input_port().FixValue(context.get(), torque);

dut.CalcOutput(*context, output.get());
lcmt_allegro_status status =
Expand Down
14 changes: 4 additions & 10 deletions examples/bead_on_a_wire/test/bead_on_a_wire_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -31,16 +31,10 @@ class BeadOnAWireTest : public ::testing::Test {
derivatives_min_ = dut_min_->AllocateTimeDerivatives();

// Fix unused input ports.
std::unique_ptr<systems::BasicVector<double>> input_abs =
std::make_unique<systems::BasicVector<double>>(3);
std::unique_ptr<systems::BasicVector<double>> input_min =
std::make_unique<systems::BasicVector<double>>(1);
input_abs->SetAtIndex(0, 0.0);
input_abs->SetAtIndex(1, 0.0);
input_abs->SetAtIndex(2, 0.0);
input_min->SetAtIndex(0, 0.0);
context_abs_->FixInputPort(0, std::move(input_abs));
context_min_->FixInputPort(0, std::move(input_min));
const Vector3<double> input_abs(0.0, 0.0, 0.0);
const double input_min = 0.0;
dut_abs_->get_input_port(0).FixValue(context_abs_.get(), input_abs);
dut_min_->get_input_port(0).FixValue(context_min_.get(), input_min);
}

std::unique_ptr<BeadOnAWire<double>> dut_abs_; //< A device under test.
Expand Down
4 changes: 1 addition & 3 deletions examples/kuka_iiwa_arm/test/iiwa_lcm_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,7 @@ GTEST_TEST(IiwaLcmTest, IiwaContactResultsToExternalTorque) {
systems::ContactResults<double> contact_results;
contact_results.set_generalized_contact_force(expected);

context->FixInputPort(0,
AbstractValue::Make<systems::ContactResults<double>>(
contact_results));
dut.get_input_port(0).FixValue(context.get(), contact_results);

// Check output.
dut.CalcOutput(*context, output.get());
Expand Down
99 changes: 42 additions & 57 deletions examples/kuka_iiwa_arm/test/kuka_torque_controller_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,26 +51,21 @@ GTEST_TEST(KukaTorqueControllerTest, GravityCompensationTest) {
std::unique_ptr<systems::SystemOutput<double>> output =
controller.AllocateOutput();

auto estimated_state_input =
std::make_unique<BasicVector<double>>(2 * kIiwaArmNumJoints);
estimated_state_input->get_mutable_value() << q, v;

auto desired_state_input =
std::make_unique<BasicVector<double>>(2 * kIiwaArmNumJoints);
desired_state_input->get_mutable_value() << q_des, v_des;

auto desired_torque_input =
std::make_unique<BasicVector<double>>(kIiwaArmNumJoints);
desired_torque_input->get_mutable_value() << torque_des;

context->FixInputPort(
controller.get_input_port_estimated_state().get_index(),
std::move(estimated_state_input));
context->FixInputPort(controller.get_input_port_desired_state().get_index(),
std::move(desired_state_input));
context->FixInputPort(
controller.get_input_port_commanded_torque().get_index(),
std::move(desired_torque_input));
VectorX<double> estimated_state_input(2 * kIiwaArmNumJoints);
estimated_state_input << q, v;

VectorX<double> desired_state_input(2 * kIiwaArmNumJoints);
desired_state_input << q_des, v_des;

VectorX<double> desired_torque_input(kIiwaArmNumJoints);
desired_torque_input << torque_des;

controller.get_input_port_estimated_state().FixValue(context.get(),
estimated_state_input);
controller.get_input_port_desired_state().FixValue(context.get(),
desired_state_input);
controller.get_input_port_commanded_torque().FixValue(context.get(),
desired_torque_input);

// Compute gravity compensation torque.
Eigen::VectorXd zero_velocity = Eigen::VectorXd::Zero(kIiwaArmNumJoints);
Expand Down Expand Up @@ -122,26 +117,21 @@ GTEST_TEST(KukaTorqueControllerTest, SpringTorqueTest) {
std::unique_ptr<systems::SystemOutput<double>> output =
controller.AllocateOutput();

auto estimated_state_input =
std::make_unique<BasicVector<double>>(2 * kIiwaArmNumJoints);
estimated_state_input->get_mutable_value() << q, v;
VectorX<double> estimated_state_input(2 * kIiwaArmNumJoints);
estimated_state_input << q, v;

auto desired_state_input =
std::make_unique<BasicVector<double>>(2 * kIiwaArmNumJoints);
desired_state_input->get_mutable_value() << q_des, v_des;
VectorX<double> desired_state_input(2 * kIiwaArmNumJoints);
desired_state_input << q_des, v_des;

auto desired_torque_input =
std::make_unique<BasicVector<double>>(kIiwaArmNumJoints);
desired_torque_input->get_mutable_value() << torque_des;
VectorX<double> desired_torque_input(kIiwaArmNumJoints);
desired_torque_input << torque_des;

context->FixInputPort(
controller.get_input_port_estimated_state().get_index(),
std::move(estimated_state_input));
context->FixInputPort(controller.get_input_port_desired_state().get_index(),
std::move(desired_state_input));
context->FixInputPort(
controller.get_input_port_commanded_torque().get_index(),
std::move(desired_torque_input));
controller.get_input_port_estimated_state().FixValue(context.get(),
estimated_state_input);
controller.get_input_port_desired_state().FixValue(context.get(),
desired_state_input);
controller.get_input_port_commanded_torque().FixValue(context.get(),
desired_torque_input);

// Compute gravity compensation torque.
Eigen::VectorXd zero_velocity = Eigen::VectorXd::Zero(kIiwaArmNumJoints);
Expand Down Expand Up @@ -196,26 +186,21 @@ GTEST_TEST(KukaTorqueControllerTest, DampingTorqueTest) {
std::unique_ptr<systems::SystemOutput<double>> output =
controller.AllocateOutput();

auto estimated_state_input =
std::make_unique<BasicVector<double>>(2 * kIiwaArmNumJoints);
estimated_state_input->get_mutable_value() << q, v;

auto desired_state_input =
std::make_unique<BasicVector<double>>(2 * kIiwaArmNumJoints);
desired_state_input->get_mutable_value() << q_des, v_des;

auto desired_torque_input =
std::make_unique<BasicVector<double>>(kIiwaArmNumJoints);
desired_torque_input->get_mutable_value() << torque_des;

context->FixInputPort(
controller.get_input_port_estimated_state().get_index(),
std::move(estimated_state_input));
context->FixInputPort(controller.get_input_port_desired_state().get_index(),
std::move(desired_state_input));
context->FixInputPort(
controller.get_input_port_commanded_torque().get_index(),
std::move(desired_torque_input));
VectorX<double> estimated_state_input(2 * kIiwaArmNumJoints);
estimated_state_input << q, v;

VectorX<double> desired_state_input(2 * kIiwaArmNumJoints);
desired_state_input << q_des, v_des;

VectorX<double> desired_torque_input(kIiwaArmNumJoints);
desired_torque_input << torque_des;

controller.get_input_port_estimated_state().FixValue(context.get(),
estimated_state_input);
controller.get_input_port_desired_state().FixValue(context.get(),
desired_state_input);
controller.get_input_port_commanded_torque().FixValue(context.get(),
desired_torque_input);

// Compute gravity compensation torque.
Eigen::VectorXd zero_velocity = Eigen::VectorXd::Zero(kIiwaArmNumJoints);
Expand Down
4 changes: 2 additions & 2 deletions examples/manipulation_station/end_effector_teleop_sliders.py
Original file line number Diff line number Diff line change
Expand Up @@ -281,8 +281,8 @@ def DoCalcOutput(self, context, output):
station_context = diagram.GetMutableSubsystemContext(
station, simulator.get_mutable_context())

station_context.FixInputPort(station.GetInputPort(
"iiwa_feedforward_torque").get_index(), np.zeros(7))
station.GetInputPort("iiwa_feedforward_torque").FixValue(station_context,
np.zeros(7))

simulator.AdvanceTo(1e-6)
q0 = station.GetOutputPort("iiwa_position_measured").Eval(
Expand Down
4 changes: 2 additions & 2 deletions examples/manipulation_station/joint_teleop.py
Original file line number Diff line number Diff line change
Expand Up @@ -90,8 +90,8 @@
station_context = diagram.GetMutableSubsystemContext(
station, simulator.get_mutable_context())

station_context.FixInputPort(station.GetInputPort(
"iiwa_feedforward_torque").get_index(), np.zeros(7))
station.GetInputPort("iiwa_feedforward_torque").FixValue(station_context,
np.zeros(7))

# Eval the output port once to read the initial positions of the IIWA.
simulator.AdvanceTo(1e-6)
Expand Down
14 changes: 5 additions & 9 deletions examples/manipulation_station/proof_of_life.cc
Original file line number Diff line number Diff line change
Expand Up @@ -93,20 +93,16 @@ int do_main(int argc, char* argv[]) {

// Position command should hold the arm at the initial state.
Eigen::VectorXd q0 = station->GetIiwaPosition(station_context);
station_context.FixInputPort(
station->GetInputPort("iiwa_position").get_index(), q0);
station->GetInputPort("iiwa_position").FixValue(&station_context, q0);

// Zero feed-forward torque.
station_context.FixInputPort(
station->GetInputPort("iiwa_feedforward_torque").get_index(),
VectorXd::Zero(station->num_iiwa_joints()));
station->GetInputPort("iiwa_feedforward_torque")
.FixValue(&station_context, VectorXd::Zero(station->num_iiwa_joints()));

// Nominal WSG position is open.
station_context.FixInputPort(
station->GetInputPort("wsg_position").get_index(), Vector1d(0.1));
station->GetInputPort("wsg_position").FixValue(&station_context, 0.1);
// Force limit at 40N.
station_context.FixInputPort(
station->GetInputPort("wsg_force_limit").get_index(), Vector1d(40.0));
station->GetInputPort("wsg_force_limit").FixValue(&station_context, 40.0);

if (!FLAGS_test) {
std::random_device rd;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,15 +19,12 @@ GTEST_TEST(ManipulationStationHardwareInterfaceTest, CheckPorts) {
auto context = station.CreateDefaultContext();

// Check sizes and names of the input ports.
context->FixInputPort(station.GetInputPort("iiwa_position").get_index(),
VectorXd::Zero(kNumIiwaDofs));
context->FixInputPort(
station.GetInputPort("iiwa_feedforward_torque").get_index(),
VectorXd::Zero(kNumIiwaDofs));
context->FixInputPort(station.GetInputPort("wsg_position").get_index(),
Vector1d::Zero());
context->FixInputPort(station.GetInputPort("wsg_force_limit").get_index(),
Vector1d::Zero());
station.GetInputPort("iiwa_position")
.FixValue(context.get(), VectorXd::Zero(kNumIiwaDofs));
station.GetInputPort("iiwa_feedforward_torque")
.FixValue(context.get(), VectorXd::Zero(kNumIiwaDofs));
station.GetInputPort("wsg_position").FixValue(context.get(), 0.);
station.GetInputPort("wsg_force_limit").FixValue(context.get(), 0.);

// Check sizes and names of the output ports.
EXPECT_EQ(station.GetOutputPort("iiwa_position_commanded")
Expand Down
31 changes: 12 additions & 19 deletions examples/manipulation_station/test/manipulation_station_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -73,22 +73,20 @@ GTEST_TEST(ManipulationStationTest, CheckPlantBasics) {
}

// Check position command pass through.
context->FixInputPort(station.GetInputPort("iiwa_position").get_index(),
q_command);
station.GetInputPort("iiwa_position").FixValue(context.get(), q_command);
EXPECT_TRUE(CompareMatrices(q_command,
station.GetOutputPort("iiwa_position_commanded")
.Eval<BasicVector<double>>(*context)
.get_value()));

// Check feedforward_torque command.
context->FixInputPort(
station.GetInputPort("iiwa_feedforward_torque").get_index(),
VectorXd::Zero(7));
station.GetInputPort("iiwa_feedforward_torque")
.FixValue(context.get(), VectorXd::Zero(7));
VectorXd tau_with_no_ff = station.GetOutputPort("iiwa_torque_commanded")
.Eval<BasicVector<double>>(*context)
.get_value();
context->FixInputPort(
station.GetInputPort("iiwa_feedforward_torque").get_index(), tau_ff);
station.GetInputPort("iiwa_feedforward_torque")
.FixValue(context.get(), tau_ff);
EXPECT_TRUE(CompareMatrices(tau_with_no_ff + tau_ff,
station.GetOutputPort("iiwa_torque_commanded")
.Eval<BasicVector<double>>(*context)
Expand All @@ -97,10 +95,8 @@ GTEST_TEST(ManipulationStationTest, CheckPlantBasics) {
// All ports must be connected if later on we'll ask questions like: "what's
// the external contact torque?". We therefore fix the gripper related ports.
double wsg_position = station.GetWsgPosition(*context);
context->FixInputPort(station.GetInputPort("wsg_position").get_index(),
Vector1d(wsg_position));
context->FixInputPort(station.GetInputPort("wsg_force_limit").get_index(),
Vector1d(40));
station.GetInputPort("wsg_position").FixValue(context.get(), wsg_position);
station.GetInputPort("wsg_force_limit").FixValue(context.get(), 40.);

// Check iiwa_torque_commanded == iiwa_torque_measured.
EXPECT_TRUE(CompareMatrices(station.GetOutputPort("iiwa_torque_commanded")
Expand Down Expand Up @@ -145,16 +141,13 @@ GTEST_TEST(ManipulationStationTest, CheckDynamics) {
station.SetIiwaPosition(context.get(), iiwa_position);
station.SetIiwaVelocity(context.get(), iiwa_velocity);

context->FixInputPort(station.GetInputPort("iiwa_position").get_index(),
station.GetInputPort("iiwa_position").FixValue(context.get(),
iiwa_position);
context->FixInputPort(
station.GetInputPort("iiwa_feedforward_torque").get_index(),
VectorXd::Zero(7));
station.GetInputPort("iiwa_feedforward_torque").FixValue(
context.get(), VectorXd::Zero(7));
double wsg_position = station.GetWsgPosition(*context);
context->FixInputPort(station.GetInputPort("wsg_position").get_index(),
Vector1d(wsg_position));
context->FixInputPort(station.GetInputPort("wsg_force_limit").get_index(),
Vector1d(40));
station.GetInputPort("wsg_position").FixValue(context.get(), wsg_position);
station.GetInputPort("wsg_force_limit").FixValue(context.get(), 40.);

// Set desired position to actual position and the desired velocity to the
// actual velocity.
Expand Down
13 changes: 6 additions & 7 deletions examples/multibody/acrobot/run_lqr.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ using multibody::Parser;
using multibody::JointActuator;
using multibody::RevoluteJoint;
using systems::Context;
using systems::InputPort;
using Eigen::Vector2d;

namespace examples {
Expand Down Expand Up @@ -68,12 +69,10 @@ std::unique_ptr<systems::AffineSystem<double>> MakeBalancingLQRController(
std::unique_ptr<Context<double>> context = acrobot.CreateDefaultContext();

// Set nominal actuation torque to zero.
const int actuation_port_index =
acrobot.get_actuation_input_port().get_index();
context->FixInputPort(actuation_port_index, Vector1d::Constant(0.0));
context->FixInputPort(
acrobot.get_applied_generalized_force_input_port().get_index(),
Vector2d::Constant(0.0));
const InputPort<double>& actuation_port = acrobot.get_actuation_input_port();
actuation_port.FixValue(context.get(), 0.0);
acrobot.get_applied_generalized_force_input_port().FixValue(
context.get(), Vector2d::Constant(0.0));

shoulder.set_angle(context.get(), M_PI);
shoulder.set_angular_rate(context.get(), 0.0);
Expand All @@ -91,7 +90,7 @@ std::unique_ptr<systems::AffineSystem<double>> MakeBalancingLQRController(
return systems::controllers::LinearQuadraticRegulator(
acrobot, *context, Q, R,
Eigen::Matrix<double, 0, 0>::Zero() /* No cross state/control costs */,
actuation_port_index);
actuation_port.get_index());
}

int do_main() {
Expand Down
3 changes: 1 addition & 2 deletions examples/multibody/cart_pole/cart_pole_passive_simulation.cc
Original file line number Diff line number Diff line change
Expand Up @@ -75,8 +75,7 @@ int do_main() {
diagram->GetMutableSubsystemContext(cart_pole, diagram_context.get());

// There is no input actuation in this example for the passive dynamics.
cart_pole_context.FixInputPort(
cart_pole.get_actuation_input_port().get_index(), Vector1d(0));
cart_pole.get_actuation_input_port().FixValue(&cart_pole_context, 0.);

// Get joints so that we can set initial conditions.
const PrismaticJoint<double>& cart_slider =
Expand Down
3 changes: 1 addition & 2 deletions examples/multibody/cart_pole/test/cart_pole_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,7 @@ class CartPoleTest : public ::testing::Test {

// Create a context to store the state for this model:
context_ = cart_pole_.CreateDefaultContext();
context_->FixInputPort(cart_pole_.get_actuation_input_port().get_index(),
Vector1d(0));
cart_pole_.get_actuation_input_port().FixValue(context_.get(), 0.);
}

// Makes the mass matrix for the cart-pole system.
Expand Down
8 changes: 3 additions & 5 deletions examples/particles/test/particle_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -68,11 +68,9 @@ TYPED_TEST_P(ParticleTest, DerivativesTest) {
// Set input.
const systems::InputPort<TypeParam>& input_port =
this->dut_->get_input_port(0);
auto input = std::make_unique<systems::BasicVector<TypeParam>>(
input_port.size());
input->SetZero();
input->SetAtIndex(0, static_cast<TypeParam>(1.0)); // u0 = 1 m/s^2
this->context_->FixInputPort(0, std::move(input));
VectorX<TypeParam> input = VectorX<TypeParam>::Zero(input_port.size());
input[0] = static_cast<TypeParam>(1.0); // u0 = 1 m/s^2
this->dut_->get_input_port(0).FixValue(this->context_.get(), input);
// Set state.
systems::VectorBase<TypeParam>& continuous_state_vector =
this->context_->get_mutable_continuous_state_vector();
Expand Down
Loading

0 comments on commit 9056a68

Please sign in to comment.