Skip to content

Commit

Permalink
Replace deprecated calls: set_time -> SetTime, set_accuracy -> SetAcc…
Browse files Browse the repository at this point in the history
  • Loading branch information
sherm1 authored Mar 29, 2019
1 parent 8cc5011 commit 6e9c34a
Show file tree
Hide file tree
Showing 43 changed files with 107 additions and 80 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ void DoTrajectoryTest(InterpolatorType interp_type) {
}

for (const TrajectoryTestCase& kase : cases) {
context->set_time(kase.time);
context->SetTime(kase.time);
dut.CalcUnrestrictedUpdate(*context, &context->get_mutable_state());
dut.CalcOutput(*context, output.get());
const double position =
Expand All @@ -176,7 +176,7 @@ void DoTrajectoryTest(InterpolatorType interp_type) {
if (interp_type == InterpolatorType::Cubic ||
interp_type == InterpolatorType::ZeroOrderHold ||
interp_type == InterpolatorType::Pchip) {
context->set_time(t.back() + 0.01);
context->SetTime(t.back() + 0.01);
dut.CalcUnrestrictedUpdate(*context, &context->get_mutable_state());
dut.CalcOutput(*context, output.get());
const double velocity =
Expand All @@ -193,7 +193,7 @@ void DoTrajectoryTest(InterpolatorType interp_type) {

// Check that sending an empty plan causes us to continue to output
// the same commanded position.
context->set_time(1);
context->SetTime(1);
dut.CalcUnrestrictedUpdate(*context, &context->get_mutable_state());
dut.CalcOutput(*context, output.get());
double position =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ VectorX<double> SimulatePlantToRest::Run(const VectorX<double>& q_ik,
.get_mutable_continuous_state_vector()
.SetFromVector(x_initial);
simulator.Initialize();
simulator.get_mutable_context().set_time(0.0);
simulator.get_mutable_context().SetTime(0.0);

simulator.reset_integrator<systems::RungeKutta2Integrator<double>>(
*diagram_, 0.0001, &simulator.get_mutable_context());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ GTEST_TEST(QpOutputTranslatorTest, QpOutputTranslatorTest) {
auto context = dut->CreateDefaultContext();
auto output = dut->AllocateOutput();

context->set_time(3.);
context->SetTime(3.);

auto qp_output = std::make_unique<QpOutput>(GetDofNames(*robot));
for (int i = 0; i < qp_output->dof_torques().size(); i++) {
Expand Down
10 changes: 5 additions & 5 deletions automotive/test/maliput_railcar_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -316,7 +316,7 @@ class MaliputRailcarTest : public ::testing::Test {
params.set_velocity_limit_kp(8);
SetParams(params);

context_->set_time(straight_lane->length() / kForwardSpeed);
context_->SetTime(straight_lane->length() / kForwardSpeed);

// Verifies that MaliputRailcar::DoCalcUnrestrictedUpdate() switches to the
// start of curved lane when it is traveling forward and reaches the end of
Expand Down Expand Up @@ -829,7 +829,7 @@ TEST_F(MaliputRailcarTest, DoCalcNextUpdateTimeDragwayWithS) {

// Verifies that the time till reaching the end of the lane is equal to the
// lane length divided by the vehicle's speed.
context_->set_time(0);
context_->SetTime(0);
continuous_state()->set_s(0);
continuous_state()->set_speed(kSpeed);
systems::LeafCompositeEventCollection<double> events;
Expand Down Expand Up @@ -868,7 +868,7 @@ TEST_F(MaliputRailcarTest, DoCalcNextUpdateTimeDragwayAgainstS) {
// Verifies that the time till reaching the end of the lane is equal to the
// lane length divided by the vehicle's speed.
systems::LeafCompositeEventCollection<double> events;
context_->set_time(0);
context_->SetTime(0);
continuous_state()->set_s(lane->length());
continuous_state()->set_speed(kSpeed);
double t = dut_->CalcNextUpdateTime(*context_, &events);
Expand Down Expand Up @@ -909,7 +909,7 @@ TEST_F(MaliputRailcarTest, DoCalcNextUpdateTimeCurvedRoadWithS) {

// Verifies that the time till reaching the end of the lane is equal to the
// lane length divided by the vehicle's speed.
context_->set_time(0);
context_->SetTime(0);
continuous_state()->set_s(0);
continuous_state()->set_speed(kSpeed);
systems::LeafCompositeEventCollection<double> events;
Expand Down Expand Up @@ -950,7 +950,7 @@ TEST_F(MaliputRailcarTest, DoCalcNextUpdateTimeCurvedRoadAgainstS) {

// Verifies that the time till reaching the end of the lane is equal to the
// lane length divided by the vehicle's speed.
context_->set_time(0);
context_->SetTime(0);
continuous_state()->set_s(lane->length());
continuous_state()->set_speed(kSpeed);
systems::LeafCompositeEventCollection<double> events;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -226,10 +226,10 @@ def test_drake_visualizer_api(self):
context = viz.CreateDefaultContext()
x0 = np.zeros(tree.get_num_positions() + tree.get_num_velocities())
context.FixInputPort(0, BasicVector(x0))
context.set_time(0.)
context.SetTime(0.)
viz.Publish(context)
# Use a small time period, since it uses realtime playback.
context.set_time(0.01)
context.SetTime(0.01)
viz.Publish(context)
viz.ReplayCachedSimulation()
# - Check that PublishLoadRobot can be called.
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/examples/test/compass_gait_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ def test_simulation(self):
# Create the simulator.
simulator = Simulator(compass_gait)
context = simulator.get_mutable_context()
context.set_accuracy(1e-8)
context.SetAccuracy(1e-8)

# Set the initial state.
state = context.get_mutable_continuous_state_vector()
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/examples/test/rimless_wheel_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ def test_simulation(self):
# Create the simulator.
simulator = Simulator(rimless_wheel)
context = simulator.get_mutable_context()
context.set_accuracy(1e-8)
context.SetAccuracy(1e-8)

# Set the initial state.
state = context.get_mutable_continuous_state_vector()
Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/systems/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -311,6 +311,7 @@ drake_py_unittest(
":analysis_py",
":framework_py",
":primitives_py",
"//bindings/pydrake/common/test_utilities",
"//bindings/pydrake/examples:pendulum_py",
"//bindings/pydrake/examples:rimless_wheel_py",
],
Expand Down
28 changes: 24 additions & 4 deletions bindings/pydrake/systems/framework_py_semantics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -159,11 +159,31 @@ void DefineFrameworkPySemantics(py::module m) {
py::arg("index"), py::arg("data"), py_reference_internal,
doc.Context.FixInputPort.doc_2args_index_data)
.def("get_time", &Context<T>::get_time, doc.Context.get_time.doc)
.def("SetTime", &Context<T>::SetTime, doc.Context.SetTime.doc)
.def("set_time", &Context<T>::set_time, "Use SetTime() instead.")
.def("SetAccuracy", &Context<T>::SetAccuracy,
.def("SetTime", &Context<T>::SetTime, py::arg("time_sec"),
doc.Context.SetTime.doc)
.def("set_time",
[](Context<T>* self, const T& time) {
WarnDeprecated(
"Use SetTime() instead. Will be removed on or after "
"2019-07-01.");
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
self->set_time(time);
#pragma GCC diagnostic pop
},
"Use SetTime() instead.")
.def("SetAccuracy", &Context<T>::SetAccuracy, py::arg("accuracy"),
doc.Context.SetAccuracy.doc)
.def("set_accuracy", &Context<T>::set_accuracy,
.def("set_accuracy",
[](Context<T>* self, const optional<double>& accuracy) {
WarnDeprecated(
"Use SetAccuracy() instead. Will be removed on or after "
"2019-07-01.");
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
self->set_accuracy(accuracy);
#pragma GCC diagnostic pop
},
"Use SetAccuracy() instead.")
.def("get_accuracy", &Context<T>::get_accuracy,
doc.Context.get_accuracy.doc)
Expand Down
5 changes: 5 additions & 0 deletions bindings/pydrake/systems/test/general_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@
PassThrough,
SignalLogger,
)
from pydrake.common.test_utilities.deprecation import catch_drake_warnings

# TODO(eric.cousineau): The scope of this test file and and `custom_test.py`
# is poor. Move these tests into `framework_test` and `analysis_test`, and
Expand Down Expand Up @@ -253,8 +254,12 @@ def check_output(context):

# Create simulator specifying context.
context = system.CreateDefaultContext()
with catch_drake_warnings(expected_count=1):
context.set_time(0.)
context.SetTime(0.)

with catch_drake_warnings(expected_count=1):
context.set_accuracy(1e-4)
context.SetAccuracy(1e-4)
self.assertEqual(context.get_accuracy(), 1e-4)

Expand Down
2 changes: 1 addition & 1 deletion examples/bouncing_ball/test/bouncing_ball_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ TEST_F(BouncingBallTest, Simulate) {
drake::systems::Simulator<double> simulator(*dut_, std::move(context_));
simulator.reset_integrator<systems::RungeKutta3Integrator<double>>(*dut_,
&simulator.get_mutable_context());
simulator.get_mutable_context().set_accuracy(accuracy);
simulator.get_mutable_context().SetAccuracy(accuracy);
simulator.get_mutable_integrator()->request_initial_step_size_target(1e-3);
simulator.get_mutable_integrator()->set_target_accuracy(accuracy);
simulator.Initialize();
Expand Down
2 changes: 1 addition & 1 deletion examples/compass_gait/simulate.cc
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ int DoMain() {
state.set_swingdot(-2.0);

simulator.set_target_realtime_rate(FLAGS_target_realtime_rate);
simulator.get_mutable_context().set_accuracy(1e-4);
simulator.get_mutable_context().SetAccuracy(1e-4);
simulator.AdvanceTo(10);

return 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ GTEST_TEST(JointLevelControllerTest, AtlasJointLevelControllerTest) {
auto context = dut->CreateDefaultContext();
auto output = dut->AllocateOutput();

context->set_time(3.);
context->SetTime(3.);

auto qp_output = std::make_unique<QpOutput>(GetDofNames(*robot));
for (int i = 0; i < qp_output->dof_torques().size(); i++) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ class HumanoidPlanEvalAndQpInverseDynamicsTest : public ::testing::Test {
diagram_ = builder.Build();

context_ = diagram_->CreateDefaultContext();
context_->set_time(0);
context_->SetTime(0);
output_ = diagram_->AllocateOutput();

// Initializes.
Expand Down
2 changes: 1 addition & 1 deletion examples/humanoid_controller/valkyrie_balancing_demo.cc
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ void controller_loop() {
const AbstractValue& first_msg = loop.WaitForMessage();
double msg_time =
loop.get_message_to_time_converter().GetTimeInSeconds(first_msg);
loop.get_mutable_context().set_time(msg_time);
loop.get_mutable_context().SetTime(msg_time);

// Decodes the message into q and v.
const bot_core::robot_state_t& raw_msg =
Expand Down
2 changes: 1 addition & 1 deletion examples/kinova_jaco_arm/jaco_controller.cc
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ int DoMain() {
status_sub->SetDefaultContext(&status_sub_context);

// Explicit initialization.
diagram_context.set_time(msg_time);
diagram_context.SetTime(msg_time);
auto& plan_source_context =
diagram->GetMutableSubsystemContext(*plan_source, &diagram_context);
plan_source->Initialize(msg_time, q0,
Expand Down
2 changes: 1 addition & 1 deletion examples/kuka_iiwa_arm/iiwa_controller.cc
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ int DoMain() {
status_sub->SetDefaultContext(&status_sub_context);

// Explicit initialization.
diagram_context.set_time(msg_time);
diagram_context.SetTime(msg_time);
auto& plan_interpolator_context =
diagram->GetMutableSubsystemContext(*plan_interpolator, &diagram_context);
plan_interpolator->Initialize(msg_time, q0, &plan_interpolator_context);
Expand Down
2 changes: 1 addition & 1 deletion examples/multibody/acrobot/run_lqr.cc
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,7 @@ int do_main() {
elbow.set_random_angle_distribution(0.05*gaussian(generator));

for (int i = 0; i < 5; i++) {
simulator.get_mutable_context().set_time(0.0);
simulator.get_mutable_context().SetTime(0.0);
simulator.get_system().SetRandomContext(&simulator.get_mutable_context(),
&generator);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ class ManipulatorJointSpaceControllerTest : public ::testing::Test {
diagram_ = builder.Build();

context_ = diagram_->CreateDefaultContext();
context_->set_time(0);
context_->SetTime(0);
output_ = diagram_->AllocateOutput();

// Initializes.
Expand Down
2 changes: 1 addition & 1 deletion examples/rimless_wheel/simulate.cc
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ int DoMain() {
state.set_thetadot(FLAGS_initial_angular_velocity);

simulator.set_target_realtime_rate(FLAGS_target_realtime_rate);
simulator.get_mutable_context().set_accuracy(FLAGS_accuracy);
simulator.get_mutable_context().SetAccuracy(FLAGS_accuracy);
simulator.AdvanceTo(10);

// Check that the state is still inside the expected region (I did not miss
Expand Down
16 changes: 8 additions & 8 deletions examples/rimless_wheel/test/rimless_wheel_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ GTEST_TEST(RimlessWheelTest, StepTest) {

systems::Simulator<double> simulator(rw);
auto& context = simulator.get_mutable_context();
context.set_accuracy(1e-8);
context.SetAccuracy(1e-8);

RimlessWheelContinuousState<double>& state =
rw.get_mutable_continuous_state(&context);
Expand All @@ -61,7 +61,7 @@ GTEST_TEST(RimlessWheelTest, StepTest) {
const double step_length = 2 * params.length() * sin(alpha);

// A point on that limit cycle just before a forward step:
context.set_time(0.0);
context.SetTime(0.0);
state.set_theta(params.slope() + alpha / 2.0);
toe = 0.0;
double_support = false;
Expand All @@ -80,7 +80,7 @@ GTEST_TEST(RimlessWheelTest, StepTest) {
const double threshold = 0.01;

// Walking too fast should lose energy through impact.
context.set_time(0.0);
context.SetTime(0.0);
state.set_theta(params.slope() + alpha / 2.0);
toe = 0.0;
double_support = false;
Expand All @@ -96,7 +96,7 @@ GTEST_TEST(RimlessWheelTest, StepTest) {
EXPECT_LT(rw.CalcTotalEnergy(context), initial_energy - threshold);

// Walking too slow should gain energy through impact.
context.set_time(0.0);
context.SetTime(0.0);
state.set_theta(params.slope() + alpha / 2.0);
toe = 0.0;
double_support = false;
Expand All @@ -112,7 +112,7 @@ GTEST_TEST(RimlessWheelTest, StepTest) {
EXPECT_GT(rw.CalcTotalEnergy(context), initial_energy + threshold);

// Rolling uphill should always lose energy.
context.set_time(0.0);
context.SetTime(0.0);
// Leaning uphill.
state.set_theta(params.slope() - alpha / 2.0);
state.set_thetadot(-4.);
Expand All @@ -135,7 +135,7 @@ GTEST_TEST(RimlessWheelTest, FixedPointTest) {

systems::Simulator<double> simulator(rw);
auto& context = simulator.get_mutable_context();
context.set_accuracy(1e-8);
context.SetAccuracy(1e-8);

RimlessWheelContinuousState<double>& state =
rw.get_mutable_continuous_state(&context);
Expand All @@ -151,7 +151,7 @@ GTEST_TEST(RimlessWheelTest, FixedPointTest) {
const double angle_above_touchdown = 1e-5;

// Front foot down.
context.set_time(0.0);
context.SetTime(0.0);
state.set_theta(params.slope() + alpha - angle_above_touchdown);
state.set_thetadot(0.0);
toe = 0.0;
Expand All @@ -162,7 +162,7 @@ GTEST_TEST(RimlessWheelTest, FixedPointTest) {
EXPECT_EQ(state.thetadot(), 0.0);

// Back foot down.
context.set_time(0.0);
context.SetTime(0.0);
state.set_theta(params.slope() - alpha + angle_above_touchdown);
state.set_thetadot(0.0);
toe = 0.0;
Expand Down
2 changes: 1 addition & 1 deletion manipulation/perception/test/pose_smoother_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class PoseSmootherTest : public ::testing::Test {
AbstractValue::Make(Isometry3<double>::Identity()));
input->set_value(input_pose);
context_->FixInputPort(0 /* input port ID*/, std::move(input));
context_->set_time(input_time);
context_->SetTime(input_time);

dut_->CalcUnrestrictedUpdate(*context_, &context_->get_mutable_state());
dut_->CalcOutput(*context_, output_.get());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,7 @@ void TestDrakeSolutionForSpecificInitialValue(
state_drake.SetFromVector(state_initial);

// Ensure the time stored by context is set to 0.0 (initial value).
context->set_time(0.0);
context->SetTime(0.0);

// Test Drake's calculated values for the time-derivative of the state at
// time t = 0 versus the exact (closed-form) solution.
Expand Down
6 changes: 3 additions & 3 deletions multibody/plant/test/joint_limits_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ GTEST_TEST(JointLimitsTest, PrismaticJointConvergenceTest) {
context.FixInputPort(
plant.get_actuation_input_port().get_index(),
Vector1<double>::Constant(10.0));
context.set_time(0.0);
context.SetTime(0.0);
simulator.AdvanceTo(simulation_time);

// Verify we are at rest near the upper limit.
Expand Down Expand Up @@ -183,7 +183,7 @@ GTEST_TEST(JointLimitsTest, RevoluteJoint) {
context.FixInputPort(
plant.get_actuation_input_port().get_index(),
Vector1<double>::Constant(-1.5));
context.set_time(0.0);
context.SetTime(0.0);
simulator.AdvanceTo(simulation_time);

// Verify we are at rest near the lower limit.
Expand Down Expand Up @@ -284,7 +284,7 @@ GTEST_TEST(JointLimitsTest, KukaArm) {
plant.get_actuation_input_port().get_index(),
VectorX<double>::Constant(nq, -0.4));
plant.SetDefaultContext(&context);
context.set_time(0.0);
context.SetTime(0.0);
simulator.AdvanceTo(simulation_time);
for (int joint_number = 1; joint_number <= nq; ++joint_number) {
const std::string joint_name = "iiwa_joint_" + std::to_string(joint_number);
Expand Down
Loading

0 comments on commit 6e9c34a

Please sign in to comment.