Skip to content

Commit

Permalink
Converted IntegrateWithFixedStepToTime(.) to return false rather than (
Browse files Browse the repository at this point in the history
  • Loading branch information
edrumwri authored Apr 26, 2019
1 parent f6b7139 commit 82dc8f7
Show file tree
Hide file tree
Showing 7 changed files with 52 additions and 32 deletions.
1 change: 1 addition & 0 deletions systems/analysis/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -305,6 +305,7 @@ drake_cc_googletest(
],
deps = [
":implicit_euler_integrator",
"//common/test_utilities:expect_throws_message",
"//systems/analysis/test_utilities",
"//systems/plants/spring_mass_system",
],
Expand Down
16 changes: 9 additions & 7 deletions systems/analysis/integrator_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@

#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/drake_nodiscard.h"
#include "drake/common/text_logging.h"
#include "drake/systems/analysis/dense_output.h"
#include "drake/systems/analysis/hermitian_dense_output.h"
Expand Down Expand Up @@ -640,21 +641,21 @@ class IntegratorBase {
/// @throws std::logic_error If the integrator has not been initialized or
/// `t_target` is in the past or the integrator
/// is not operating in fixed step mode.
/// @throws std::runtime_error If the integrator was unable to take a single
/// fixed step to realize `t_target`.
/// @sa IntegrateNoFurtherThanTime(), which is designed to be operated by
/// Simulator and accounts for publishing and state reinitialization.
/// @sa IntegrateWithMultipleStepsToTime(), which is also designed to be
/// operated *outside of* Simulator, but will take as many integration
/// steps as necessary until time has been stepped forward to `t_target`.
/// @returns `true` if the integrator was able to take a single fixed step to
/// `t_target`.
///
/// This method at a glance:
///
/// - For integrating ODEs/DAEs not using Simulator
/// - Fixed step integration (no step size reductions for error control or
/// integrator convergence)
/// - Takes only a single step forward.
void IntegrateWithSingleFixedStepToTime(const T& t_target) {
DRAKE_NODISCARD bool IntegrateWithSingleFixedStepToTime(const T& t_target) {
using std::max;
using std::abs;

Expand All @@ -666,10 +667,9 @@ class IntegratorBase {
if (!this->get_fixed_step_mode())
throw std::logic_error("IntegrateWithSingleFixedStepToTime() requires "
"fixed stepping.");
if (!Step(dt)) {
throw std::runtime_error("Integrator was unable to take a single fixed "
"step of the requested size.");
}

if (!Step(dt))
return false;

UpdateStepStatistics(dt);

Expand All @@ -680,6 +680,8 @@ class IntegratorBase {
ExtractDoubleOrThrow(max(t_target, context_->get_time()));
DRAKE_DEMAND(abs(context_->get_time() - t_target) < tol);
context_->SetTime(t_target);

return true;
}

/**
Expand Down
5 changes: 3 additions & 2 deletions systems/analysis/test/explicit_euler_integrator_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,8 @@ GTEST_TEST(IntegratorTest, MagDisparity) {
integrator.Initialize();

// Take a fixed integration step.
integrator.IntegrateWithSingleFixedStepToTime(context->get_time() + dt);
ASSERT_TRUE(integrator.IntegrateWithSingleFixedStepToTime(
context->get_time() + dt));
}

// Try a purely continuous system with no sampling.
Expand Down Expand Up @@ -280,7 +281,7 @@ GTEST_TEST(IntegratorTest, StepSize) {
{
const double boundary_dt = 0.0009;
const double boundary_time = context->get_time() + boundary_dt;
integrator.IntegrateWithSingleFixedStepToTime(boundary_time);
ASSERT_TRUE(integrator.IntegrateWithSingleFixedStepToTime(boundary_time));
EXPECT_EQ(t + boundary_dt, context->get_time());
t = context->get_time();
}
Expand Down
35 changes: 24 additions & 11 deletions systems/analysis/test/implicit_euler_integrator_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

#include <gtest/gtest.h>

#include "drake/common/test_utilities/expect_throws_message.h"
#include "drake/common/unused.h"
#include "drake/systems/analysis/test_utilities/discontinuous_spring_mass_damper_system.h"
#include "drake/systems/analysis/test_utilities/robertson_system.h"
#include "drake/systems/analysis/test_utilities/spring_mass_damper_system.h"
Expand Down Expand Up @@ -193,19 +195,30 @@ TEST_F(ImplicitIntegratorTest, AutoDiff) {
ImplicitEulerIntegrator<AutoDiffXd> integrator(*system, context.get());

// Set reasonable integrator parameters.
integrator.set_fixed_step_mode(true);
integrator.set_maximum_step_size(large_dt_);
integrator.request_initial_step_size_target(large_dt_);
integrator.set_target_accuracy(1e-5);
integrator.set_requested_minimum_step_size(small_dt_);
integrator.set_jacobian_computation_scheme(ImplicitIntegrator<AutoDiffXd>::
JacobianComputationScheme::kAutomatic);
integrator.Initialize();

// Integrate for one step. We expect this to throw because the integrator
// is generally unlikely to converge for such a relatively large step.
EXPECT_THROW(integrator.IntegrateWithSingleFixedStepToTime(
context_->get_time() + large_dt_), std::logic_error);

// TODO(edrumwri): Add test that an automatic differentiation of an implicit
// integrator produces the expected result.
// Integrate for one step. We expect this to throw since we've requested
// using an automatically differentiated Jacobian matrix on the AutoDiff'd
// integrator.
bool result;
DRAKE_EXPECT_THROWS_MESSAGE(result = integrator.
IntegrateWithSingleFixedStepToTime(context_->get_time() + large_dt_),
std::runtime_error,
"AutoDiff'd Jacobian not supported.*");

// Revert to forward difference and try again; we now expect no throw.
integrator.set_jacobian_computation_scheme(ImplicitIntegrator<AutoDiffXd>::
JacobianComputationScheme::kForwardDifference);
EXPECT_NO_THROW(result = integrator.IntegrateWithSingleFixedStepToTime(
context_->get_time() + large_dt_));
unused(result);
}

TEST_P(ImplicitIntegratorTest, MiscAPI) {
Expand Down Expand Up @@ -264,8 +277,8 @@ TEST_F(ImplicitIntegratorTest, FixedStepThrowsOnMultiStep) {
// Integrate to the desired step time. We expect this to throw because the
// integrator is generally unlikely to converge for such a relatively large
// step.
EXPECT_THROW(integrator.IntegrateWithSingleFixedStepToTime(
context_->get_time() + huge_dt), std::runtime_error);
EXPECT_FALSE(integrator.IntegrateWithSingleFixedStepToTime(
context_->get_time() + huge_dt));
}

TEST_F(ImplicitIntegratorTest, ContextAccess) {
Expand Down Expand Up @@ -615,8 +628,8 @@ TEST_P(ImplicitIntegratorTest, ErrorEstimation) {
spring_mass.set_velocity(context_.get(), initial_velocity[i]);

// Integrate for the desired step size.
integrator.IntegrateWithSingleFixedStepToTime(
context_->get_time() + dts[j]);
ASSERT_TRUE(integrator.IntegrateWithSingleFixedStepToTime(
context_->get_time() + dts[j]));

// Check the time.
EXPECT_NEAR(context_->get_time(), dts[j], ttol);
Expand Down
2 changes: 1 addition & 1 deletion systems/analysis/test/runge_kutta2_integrator_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ GTEST_TEST(RK3IntegratorErrorEstimatorTest, QuadraticTest) {
rk2.set_maximum_step_size(t_final);
rk2.set_fixed_step_mode(true);
rk2.Initialize();
rk2.IntegrateWithSingleFixedStepToTime(t_final);
ASSERT_TRUE(rk2.IntegrateWithSingleFixedStepToTime(t_final));

const double expected_result = t_final * (4 * t_final + 4) + C;
EXPECT_NEAR(
Expand Down
10 changes: 5 additions & 5 deletions systems/analysis/test/runge_kutta3_integrator_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ GTEST_TEST(RK3IntegratorErrorEstimatorTest, CubicTest) {
rk3.set_maximum_step_size(t_final);
rk3.set_fixed_step_mode(true);
rk3.Initialize();
rk3.IntegrateWithSingleFixedStepToTime(t_final);
ASSERT_TRUE(rk3.IntegrateWithSingleFixedStepToTime(t_final));

// Check for near-exact 3rd-order results. The measure of accuracy is a
// tolerance that scales with expected answer at t_final.
Expand All @@ -136,8 +136,8 @@ GTEST_TEST(RK3IntegratorErrorEstimatorTest, CubicTest) {
cubic_context->SetTime(0.0);
cubic_context->get_mutable_continuous_state_vector()[0] = C;
rk3.Initialize();
rk3.IntegrateWithSingleFixedStepToTime(t_final/2);
rk3.IntegrateWithSingleFixedStepToTime(t_final);
ASSERT_TRUE(rk3.IntegrateWithSingleFixedStepToTime(t_final/2));
ASSERT_TRUE(rk3.IntegrateWithSingleFixedStepToTime(t_final));
const double err_est_2h_2 =
rk3.get_error_estimate()->get_vector().GetAtIndex(0);

Expand Down Expand Up @@ -171,7 +171,7 @@ GTEST_TEST(RK3IntegratorErrorEstimatorTest, QuadraticTest) {
rk3.set_maximum_step_size(t_final);
rk3.set_fixed_step_mode(true);
rk3.Initialize();
rk3.IntegrateWithSingleFixedStepToTime(t_final);
ASSERT_TRUE(rk3.IntegrateWithSingleFixedStepToTime(t_final));

const double err_est =
rk3.get_error_estimate()->get_vector().GetAtIndex(0);
Expand All @@ -194,7 +194,7 @@ TEST_F(RK3IntegratorTest, ComparisonWithRK2) {
const double t_final = 1.0;
const int n_steps = t_final / dt;
for (int i = 1; i <= n_steps; ++i)
rk2.IntegrateWithSingleFixedStepToTime(i * dt);
ASSERT_TRUE(rk2.IntegrateWithSingleFixedStepToTime(i * dt));

// Re-integrate with RK3.
std::unique_ptr<Context<double>> rk3_context = MakePlantContext();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

#include <gtest/gtest.h>

#include "drake/common/unused.h"
#include "drake/systems/analysis/test_utilities/my_spring_mass_system.h"
#include "drake/systems/analysis/test_utilities/pleides_system.h"

Expand Down Expand Up @@ -190,7 +191,7 @@ TYPED_TEST_P(ExplicitErrorControlledIntegratorTest, ErrEstOrder) {
// Take a single step of size h.
ASSERT_EQ(this->context->get_time(), 0.0);
const double t_final = this->context->get_time() + h;
this->integrator->IntegrateWithSingleFixedStepToTime(t_final);
ASSERT_TRUE(this->integrator->IntegrateWithSingleFixedStepToTime(t_final));

// Verify that a step of h was taken.
EXPECT_NEAR(this->context->get_time(), h,
Expand All @@ -215,8 +216,9 @@ TYPED_TEST_P(ExplicitErrorControlledIntegratorTest, ErrEstOrder) {
this->spring_mass->set_velocity(this->integrator->get_mutable_context(),
initial_velocity);
this->integrator->Initialize();
this->integrator->IntegrateWithSingleFixedStepToTime(t_final / 2.0);
this->integrator->IntegrateWithSingleFixedStepToTime(t_final);
ASSERT_TRUE(this->integrator->IntegrateWithSingleFixedStepToTime(
t_final / 2.0));
ASSERT_TRUE(this->integrator->IntegrateWithSingleFixedStepToTime(t_final));
EXPECT_NEAR(this->context->get_time(), h,
std::numeric_limits<double>::epsilon());
const double x_approx_2h_h = this->context->get_continuous_state_vector().
Expand Down Expand Up @@ -375,7 +377,7 @@ TYPED_TEST_P(ExplicitErrorControlledIntegratorTest, StepToCurrentTimeNoOp) {

// Must do fixed stepping for the last test.
this->integrator->set_fixed_step_mode(true);
this->integrator->IntegrateWithSingleFixedStepToTime(t_final);
ASSERT_TRUE(this->integrator->IntegrateWithSingleFixedStepToTime(t_final));
EXPECT_EQ(this->context->get_time(), t_final);
for (int i = 0; i < x_final.size(); ++i)
EXPECT_EQ(x_final[i], this->context->get_continuous_state_vector()[i]);
Expand Down Expand Up @@ -435,8 +437,9 @@ TYPED_TEST_P(ExplicitErrorControlledIntegratorTest, IllegalFixedStep) {
this->integrator->Initialize();

ASSERT_EQ(this->context->get_time(), 0.0);
EXPECT_THROW(this->integrator->IntegrateWithSingleFixedStepToTime(1e-8),
std::logic_error);
EXPECT_THROW(unused(
this->integrator->IntegrateWithSingleFixedStepToTime(1e-8)),
std::logic_error);
}

// Verifies statistics validity for error controlled integrator.
Expand Down

0 comments on commit 82dc8f7

Please sign in to comment.