Skip to content

Commit

Permalink
Use AdvanceTo() instead of StepTo() (RobotLocomotion#11055)
Browse files Browse the repository at this point in the history
  • Loading branch information
sherm1 authored Mar 28, 2019
1 parent 63e8bf5 commit 8bde6bc
Show file tree
Hide file tree
Showing 121 changed files with 316 additions and 292 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -287,7 +287,7 @@ int do_main() {
simulator.set_target_realtime_rate(0);
simulator.get_mutable_integrator()->set_maximum_step_size(h);
simulator.Initialize();
simulator.StepTo(kTimes.back());
simulator.AdvanceTo(kTimes.back());

// Comparing the final position and orientation of the object in world frame
// to expected values.
Expand Down
2 changes: 1 addition & 1 deletion attic/manipulation/dev/test/rod2d_time_stepping.cc
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,7 @@ VectorXd RunSimulation(const bool is_analytic) {
const double h = rod2d->get_period_sec();
simulator.get_mutable_integrator()->set_maximum_step_size(h);
simulator.Initialize();
simulator.StepTo(7.5);
simulator.AdvanceTo(7.5);

VectorXd q_final = log_state->data().topRightCorner(n1, 1);
return q_final;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ VectorX<double> SimulatePlantToRest::Run(const VectorX<double>& q_ik,
step_time = 1.0;
step_delta = 0.1;
do {
simulator.StepTo(step_time);
simulator.AdvanceTo(step_time);
step_time += step_delta;
x = simulator.get_context().get_continuous_state_vector().CopyToVector();
v = x.tail(num_velocities);
Expand Down
2 changes: 1 addition & 1 deletion attic/manipulation/util/test/sim_diagram_builder_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,7 @@ GTEST_TEST(SimDiagramBuilderTest, TestSimulation) {
plant->set_state_vector(&plant_context, state0);

simulator.Initialize();
simulator.StepTo(0.02);
simulator.AdvanceTo(0.02);

auto state_output = diagram->AllocateOutput();
diagram->CalcOutput(simulator.get_context(), state_output.get());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -513,7 +513,7 @@ GTEST_TEST(DrakeVisualizerTests, TestPublishPeriod) {
VerifyLoadMessage(lcm.get_last_published_message("DRAKE_VIEWER_LOAD_ROBOT"));

for (double time = 0; time < 4; time += 0.01) {
simulator.StepTo(time);
simulator.AdvanceTo(time);
EXPECT_NEAR(simulator.get_mutable_context().get_time(), time, 1e-10);
// Note that the expected time is in milliseconds.
const double expected_time =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -197,8 +197,8 @@ TEST_F(RigidBodyTreeCloneTest, PendulumDynamicsTest) {
const SignalLogger<double>& original_logger = original_diagram.get_logger();
const SignalLogger<double>& cloned_logger = cloned_diagram.get_logger();

original_simulator.StepTo(swing_period);
cloned_simulator.StepTo(swing_period);
original_simulator.AdvanceTo(swing_period);
cloned_simulator.AdvanceTo(swing_period);
ASSERT_TRUE(CompareMatrices(original_logger.data(), cloned_logger.data()));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ GTEST_TEST(testQpInverseDynamicsSystem, IiwaInverseDynamics) {
std::unique_ptr<SystemOutput<double>> output =
diagram->AllocateOutput();
sim.Initialize();
sim.StepTo(controller->get_control_dt());
sim.AdvanceTo(controller->get_control_dt());

// Gets the output from the plan eval block.
diagram->CalcOutput(sim.get_context(), output.get());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ int exec(int argc, char* argv[]) {
Simulator<double> simulator(diagram, std::move(context));
simulator.Initialize();
simulator.set_target_realtime_rate(1);
simulator.StepTo(FLAGS_simulation_sec);
simulator.AdvanceTo(FLAGS_simulation_sec);
return 0;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -155,7 +155,7 @@ GTEST_TEST(TestAccelerometer, TestSensorAttachedToSwingingPendulum) {
const RigidBodyTree<double>& tree = diagram.get_tree();

const double kStepToTime = 0.01;
simulator.StepTo(kStepToTime);
simulator.AdvanceTo(kStepToTime);

const Context<double>& simulator_context = simulator.get_context();
const Context<double>& logger_context =
Expand Down
2 changes: 1 addition & 1 deletion automotive/automotive_simulator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -796,7 +796,7 @@ template <typename T>
void AutomotiveSimulator<T>::StepBy(const T& time_step) {
const T time = simulator_->get_context().get_time();
SPDLOG_TRACE(drake::log(), "Time is now {}", time);
simulator_->StepTo(time + time_step);
simulator_->AdvanceTo(time + time_step);
}

template <typename T>
Expand Down
4 changes: 2 additions & 2 deletions automotive/test/automotive_simulator_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -377,14 +377,14 @@ GTEST_TEST(AutomotiveSimulatorTest, TestIdmControlledSimpleCarAutoDiff) {
auto plant_simulator =
std::make_unique<systems::Simulator<double>>(plant);

plant_simulator->StepTo(0.5);
plant_simulator->AdvanceTo(0.5);

// Converts to AutoDiffXd.
auto plant_ad = plant.ToAutoDiffXd();
auto plant_ad_simulator =
std::make_unique<systems::Simulator<AutoDiffXd>>(*plant_ad);

plant_ad_simulator->StepTo(0.5);
plant_ad_simulator->AdvanceTo(0.5);
}

// Returns the x-position of the vehicle based on an lcmt_viewer_draw message.
Expand Down
2 changes: 1 addition & 1 deletion automotive/test/trajectory_car_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ TYPED_TEST(TrajectoryCarTest, ConstantSpeedTest) {
simulator.Initialize();

for (double time = start_time; time <= end_time; time += 0.1) {
simulator.StepTo(time - start_time);
simulator.AdvanceTo(time - start_time);

const double fractional_progress =
std::min(std::max(0.0, (time * it.speed) / total_distance), 1.0);
Expand Down
2 changes: 1 addition & 1 deletion automotive/test/trajectory_follower_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ GTEST_TEST(TrajectoryFollowerTest, Outputs) {

const double end_time = it.distance / kSpeed;
for (double time = 0.; time <= end_time; time += 0.1) {
simulator.StepTo(time);
simulator.AdvanceTo(time);

const double scalar =
std::min(std::max(0.0, (time * kSpeed) / it.distance), 1.);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ def main():
simulator.set_publish_every_time_step(False)
simulator.set_target_realtime_rate(args.target_realtime_rate)
simulator.Initialize()
simulator.StepTo(args.simulation_time)
simulator.AdvanceTo(args.simulation_time)


if __name__ == "__main__":
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/examples/test/acrobot_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ def test_simulation(self):

# Simulate (and make sure the state actually changes).
initial_state = state.CopyToVector()
simulator.StepTo(1.0)
simulator.AdvanceTo(1.0)

self.assertLessEqual(acrobot.CalcPotentialEnergy(context) +
acrobot.CalcKineticEnergy(context),
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 @@ -55,5 +55,5 @@ def test_simulation(self):

# Simulate (and make sure the state actually changes).
initial_state = state.CopyToVector()
simulator.StepTo(1.0)
simulator.AdvanceTo(1.0)
self.assertFalse((state.CopyToVector() == initial_state).any())
2 changes: 1 addition & 1 deletion bindings/pydrake/examples/test/pendulum_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -57,5 +57,5 @@ def test_simulation(self):

# Simulate (and make sure the state actually changes).
initial_state = state.CopyToVector()
simulator.StepTo(1.0)
simulator.AdvanceTo(1.0)
self.assertFalse((state.CopyToVector() == initial_state).any())
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 @@ -47,5 +47,5 @@ def test_simulation(self):

# Simulate (and make sure the state actually changes).
initial_state = state.CopyToVector()
simulator.StepTo(1.0)
simulator.AdvanceTo(1.0)
self.assertFalse((state.CopyToVector() == initial_state).any())
2 changes: 1 addition & 1 deletion bindings/pydrake/examples/test/van_der_pol_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ def test_simulation(self):

# Simulate (and make sure the state actually changes).
initial_state = state.CopyToVector()
simulator.StepTo(1.0)
simulator.AdvanceTo(1.0)
self.assertFalse((state.CopyToVector() == initial_state).any())

def test_ports(self):
Expand Down
3 changes: 2 additions & 1 deletion bindings/pydrake/systems/analysis_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,8 @@ PYBIND11_MODULE(analysis, m) {
py::keep_alive<3, 1>(), doc.Simulator.ctor.doc)
.def("Initialize", &Simulator<T>::Initialize,
doc.Simulator.Initialize.doc)
.def("StepTo", &Simulator<T>::StepTo, doc.Simulator.StepTo.doc)
.def("AdvanceTo", &Simulator<T>::AdvanceTo, doc.Simulator.AdvanceTo.doc)
.def("StepTo", &Simulator<T>::StepTo, "Use AdvanceTo() instead.")
.def("get_context", &Simulator<T>::get_context, py_reference_internal,
doc.Simulator.get_context.doc)
.def("get_integrator", &Simulator<T>::get_integrator,
Expand Down
4 changes: 2 additions & 2 deletions bindings/pydrake/systems/test/custom_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ def test_adder_simulation(self):

simulator = Simulator(diagram, context)
simulator.Initialize()
simulator.StepTo(1)
simulator.AdvanceTo(1)
# Ensure that we have the outputs we want.
value = (diagram.GetMutableSubsystemContext(zoh, context)
.get_discrete_state_vector().get_value())
Expand Down Expand Up @@ -297,7 +297,7 @@ def _on_periodic(self, context, event):
system = TrivialSystem()
simulator = Simulator(system)
# Stepping to 0.99 so that we get exactly one periodic event.
simulator.StepTo(0.99)
simulator.AdvanceTo(0.99)
self.assertTrue(system.called_per_step)
self.assertTrue(system.called_periodic)

Expand Down
6 changes: 3 additions & 3 deletions bindings/pydrake/systems/test/general_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -249,7 +249,7 @@ def check_output(context):
self.assertTrue(simulator.get_context() is
simulator.get_mutable_context())
check_output(simulator.get_context())
simulator.StepTo(1)
simulator.AdvanceTo(1)

# Create simulator specifying context.
context = system.CreateDefaultContext()
Expand All @@ -262,7 +262,7 @@ def check_output(context):
simulator = Simulator_[T](system, context)
self.assertTrue(simulator.get_context() is context)
check_output(context)
simulator.StepTo(1)
simulator.AdvanceTo(1)

def test_copy(self):
# Copy a context using `deepcopy` or `clone`.
Expand Down Expand Up @@ -337,7 +337,7 @@ def test_diagram_simulation(self):
times = np.linspace(0, 1, n)
context_log = []
for t in times:
simulator.StepTo(t)
simulator.AdvanceTo(t)
# Record snapshot of *entire* context.
context_log.append(context.Clone())

Expand Down
10 changes: 5 additions & 5 deletions bindings/pydrake/systems/test/meshcat_visualizer_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ def test_cart_pole(self):

simulator = Simulator(diagram, diagram_context)
simulator.set_publish_every_time_step(False)
simulator.StepTo(.1)
simulator.AdvanceTo(.1)

def test_kuka(self):
"""Kuka IIWA with mesh geometry."""
Expand Down Expand Up @@ -110,7 +110,7 @@ def test_kuka(self):

simulator = Simulator(diagram, diagram_context)
simulator.set_publish_every_time_step(False)
simulator.StepTo(.1)
simulator.AdvanceTo(.1)

def test_contact_force(self):
"""A block sitting on a table."""
Expand Down Expand Up @@ -179,7 +179,7 @@ def test_contact_force(self):

simulator = Simulator(diagram, diagram_context)
simulator.set_publish_every_time_step(False)
simulator.StepTo(1.0)
simulator.AdvanceTo(1.0)

contact_viz_context = (
diagram.GetMutableSubsystemContext(contact_viz, diagram_context))
Expand Down Expand Up @@ -218,7 +218,7 @@ def test_texture_override(self):

simulator = Simulator(diagram, diagram_context)
simulator.set_publish_every_time_step(False)
simulator.StepTo(1.0)
simulator.AdvanceTo(1.0)

def test_point_cloud_visualization(self):
"""A small point cloud"""
Expand Down Expand Up @@ -255,7 +255,7 @@ def show_cloud(pc, use_native=False, **kwargs):
AbstractValue.Make(pc))
simulator = Simulator(diagram, diagram_context)
simulator.set_publish_every_time_step(False)
simulator.StepTo(sim_time)
simulator.AdvanceTo(sim_time)

# Generate some random points that are visually noticeable.
# ~300000 makes the visualizer less responsive on my (Eric) machine.
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/systems/test/primitives_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ def test_signal_logger(self):
diagram = builder.Build()
simulator = Simulator(diagram)
kTime = 1.
simulator.StepTo(kTime)
simulator.AdvanceTo(kTime)

# Verify outputs of the every-step logger
t = logger_per_step.sample_times()
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/test/automotive_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -251,7 +251,7 @@ def test_simple_car(self):
# Initialize all the states to zero and take a simulation step.
state = context.get_mutable_continuous_state_vector()
state.SetFromVector([0.] * state.size())
simulator.StepTo(1.0)
simulator.AdvanceTo(1.0)

# Verify the outputs.
simple_car.CalcOutput(context, output)
Expand Down
2 changes: 1 addition & 1 deletion examples/acrobot/run_lqr.cc
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ int do_main() {

simulator.set_target_realtime_rate(FLAGS_realtime_factor);
simulator.Initialize();
simulator.StepTo(FLAGS_simulation_sec);
simulator.AdvanceTo(FLAGS_simulation_sec);
return 0;
}

Expand Down
2 changes: 1 addition & 1 deletion examples/acrobot/run_lqr_w_estimator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ int do_main() {
simulator.get_mutable_integrator()->set_maximum_step_size(0.01);
simulator.get_mutable_integrator()->set_fixed_step_mode(true);
simulator.Initialize();
simulator.StepTo(FLAGS_simulation_sec);
simulator.AdvanceTo(FLAGS_simulation_sec);

// Plot the results (launch call_matlab_client to see the plots).
using common::CallMatlab;
Expand Down
2 changes: 1 addition & 1 deletion examples/acrobot/run_passive.cc
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ int do_main() {

simulator.set_target_realtime_rate(FLAGS_realtime_factor);
simulator.Initialize();
simulator.StepTo(FLAGS_simulation_sec);
simulator.AdvanceTo(FLAGS_simulation_sec);
return 0;
}

Expand Down
2 changes: 1 addition & 1 deletion examples/acrobot/run_plant_w_lcm.cc
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ int DoMain() {

simulator.set_target_realtime_rate(FLAGS_realtime_factor);
simulator.Initialize();
simulator.StepTo(FLAGS_simulation_sec);
simulator.AdvanceTo(FLAGS_simulation_sec);

lcm.StopReceiveThread();
return 0;
Expand Down
2 changes: 1 addition & 1 deletion examples/acrobot/run_swing_up.cc
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ int do_main() {
state->set_theta2dot(0.02);

simulator.set_target_realtime_rate(FLAGS_realtime_factor);
simulator.StepTo(FLAGS_simulation_sec);
simulator.AdvanceTo(FLAGS_simulation_sec);

DRAKE_DEMAND(std::abs(math::wrap_to(state->theta1(), 0., 2. * M_PI) - M_PI) <
1e-2);
Expand Down
2 changes: 1 addition & 1 deletion examples/acrobot/test/run_swing_up_traj_optimization.cc
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ int do_main() {

simulator.set_target_realtime_rate(FLAGS_realtime_factor);
simulator.Initialize();
simulator.StepTo(pp_xtraj.end_time());
simulator.AdvanceTo(pp_xtraj.end_time());
return 0;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -199,7 +199,7 @@ void DoMain() {
&simulator.get_mutable_context()),
VectorX<double>::Zero(plant.num_actuators()));

simulator.StepTo(FLAGS_simulation_time);
simulator.AdvanceTo(FLAGS_simulation_time);

lcm.StopReceiveThread();
}
Expand Down
2 changes: 1 addition & 1 deletion examples/allegro_hand/run_allegro_constant_load_demo.cc
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ void DoMain() {
simulator.set_publish_every_time_step(true);
simulator.set_target_realtime_rate(FLAGS_target_realtime_rate);
simulator.Initialize();
simulator.StepTo(FLAGS_simulation_time);
simulator.AdvanceTo(FLAGS_simulation_time);
}

} // namespace allegro_hand
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 @@ -177,7 +177,7 @@ TEST_F(BouncingBallTest, Simulate) {
xc.SetAtIndex(1, v0);

// Integrate.
simulator.StepTo(t_final);
simulator.AdvanceTo(t_final);
EXPECT_EQ(simulator.get_mutable_context().get_time(), t_final);

// Check against closed form solution for the bouncing ball. We anticipate
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 @@ -77,7 +77,7 @@ int DoMain() {

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

return 0;
}
Expand Down
2 changes: 1 addition & 1 deletion examples/contact_model/bowling_ball.cc
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,7 @@ int main() {

plant.set_state_vector(&plant_context, initial_state);

simulator.StepTo(FLAGS_sim_duration);
simulator.AdvanceTo(FLAGS_sim_duration);

return 0;
}
Expand Down
Loading

0 comments on commit 8bde6bc

Please sign in to comment.