Skip to content

Commit

Permalink
Use std::optional instead of drake::optional in systems (RobotLocomot…
Browse files Browse the repository at this point in the history
  • Loading branch information
jamiesnape authored Oct 30, 2019
1 parent 3ae693f commit 15d1839
Show file tree
Hide file tree
Showing 42 changed files with 141 additions and 134 deletions.
10 changes: 5 additions & 5 deletions systems/analysis/antiderivative_function.h
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
#pragma once

#include <memory>
#include <optional>
#include <utility>
#include <vector>

#include "drake/common/drake_copyable.h"
#include "drake/common/drake_optional.h"
#include "drake/common/eigen_types.h"
#include "drake/common/unused.h"
#include "drake/systems/analysis/scalar_dense_output.h"
Expand Down Expand Up @@ -74,12 +74,12 @@ class AntiderivativeFunction {
/// Constructor that specifies all values.
/// @param v_in Specified lower integration bound v.
/// @param k_in Specified parameter vector 𝐤.
SpecifiedValues(const optional<T>& v_in,
const optional<VectorX<T>>& k_in)
SpecifiedValues(const std::optional<T>& v_in,
const std::optional<VectorX<T>>& k_in)
: v(v_in), k(k_in) {}

optional<T> v; ///< The lower integration bound v.
optional<VectorX<T>> k; ///< The parameter vector 𝐤.
std::optional<T> v; ///< The lower integration bound v.
std::optional<VectorX<T>> k; ///< The parameter vector 𝐤.
};

/// Constructs the antiderivative function of the given
Expand Down
14 changes: 7 additions & 7 deletions systems/analysis/initial_value_problem.h
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
#pragma once

#include <memory>
#include <optional>
#include <utility>
#include <vector>

#include "drake/common/drake_copyable.h"
#include "drake/common/drake_optional.h"
#include "drake/common/eigen_types.h"
#include "drake/systems/analysis/dense_output.h"
#include "drake/systems/analysis/integrator_base.h"
Expand Down Expand Up @@ -94,9 +94,9 @@ class InitialValueProblem {
/// @param t0_in Specified initial time t₀.
/// @param x0_in Specified initial state vector 𝐱₀.
/// @param k_in Specified parameter vector 𝐤.
SpecifiedValues(const optional<T>& t0_in,
const optional<VectorX<T>>& x0_in,
const optional<VectorX<T>>& k_in)
SpecifiedValues(const std::optional<T>& t0_in,
const std::optional<VectorX<T>>& x0_in,
const std::optional<VectorX<T>>& k_in)
: t0(t0_in), x0(x0_in), k(k_in) {}

bool operator==(const SpecifiedValues& rhs) const {
Expand All @@ -107,9 +107,9 @@ class InitialValueProblem {
return !operator==(rhs);
}

optional<T> t0; ///< The initial time t₀ for the IVP.
optional<VectorX<T>> x0; ///< The initial state vector 𝐱₀ for the IVP.
optional<VectorX<T>> k; ///< The parameter vector 𝐤 for the IVP.
std::optional<T> t0; ///< The initial time t₀ for the IVP.
std::optional<VectorX<T>> x0; ///< The initial state vector 𝐱₀ for the IVP.
std::optional<VectorX<T>> k; ///< The parameter vector 𝐤 for the IVP.
};

/// Constructs an IVP described by the given @p ode_function, using
Expand Down
14 changes: 7 additions & 7 deletions systems/analysis/scalar_initial_value_problem.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,11 @@

#include <algorithm>
#include <memory>
#include <optional>
#include <utility>
#include <vector>

#include "drake/common/drake_copyable.h"
#include "drake/common/drake_optional.h"
#include "drake/common/eigen_types.h"
#include "drake/systems/analysis/initial_value_problem.h"
#include "drake/systems/analysis/scalar_view_dense_output.h"
Expand Down Expand Up @@ -79,14 +79,14 @@ class ScalarInitialValueProblem {
/// @param t0_in Specified initial time t₀.
/// @param x0_in Specified initial state x₀.
/// @param k_in Specified parameter vector 𝐤.
SpecifiedValues(const optional<T>& t0_in,
const optional<T>& x0_in,
const optional<VectorX<T>>& k_in)
SpecifiedValues(const std::optional<T>& t0_in,
const std::optional<T>& x0_in,
const std::optional<VectorX<T>>& k_in)
: t0(t0_in), x0(x0_in), k(k_in) {}

optional<T> t0; ///< The initial time t₀ for the IVP.
optional<T> x0; ///< The initial state x₀ for the IVP.
optional<VectorX<T>> k; ///< The parameter vector 𝐤 for the IVP.
std::optional<T> t0; ///< The initial time t₀ for the IVP.
std::optional<T> x0; ///< The initial state x₀ for the IVP.
std::optional<VectorX<T>> k; ///< The parameter vector 𝐤 for the IVP.
};

/// Constructs an scalar IVP described by the given @p scalar_ode_function,
Expand Down
12 changes: 6 additions & 6 deletions systems/analysis/simulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <cmath>
#include <limits>
#include <memory>
#include <optional>
#include <tuple>
#include <unordered_map>
#include <utility>
Expand All @@ -13,7 +14,6 @@
#include "drake/common/autodiff.h"
#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/drake_optional.h"
#include "drake/common/extract_double.h"
#include "drake/common/text_logging.h"
#include "drake/systems/analysis/integrator_base.h"
Expand Down Expand Up @@ -531,7 +531,7 @@ class Simulator {
/// @throws std::logic_error if the accuracy is not set in the Context and
/// the integrator is not operating in fixed step mode (see
/// IntegratorBase::get_fixed_step_mode().
optional<T> GetCurrentWitnessTimeIsolation() const;
std::optional<T> GetCurrentWitnessTimeIsolation() const;

/// Gets a constant reference to the system.
/// @note a mutable reference is not available.
Expand Down Expand Up @@ -1009,7 +1009,7 @@ void Simulator<T>::AdvanceTo(const T& boundary_time) {
}

template <class T>
optional<T> Simulator<T>::GetCurrentWitnessTimeIsolation() const {
std::optional<T> Simulator<T>::GetCurrentWitnessTimeIsolation() const {
using std::max;

// TODO(edrumwri): Add ability to disable witness time isolation through
Expand All @@ -1027,7 +1027,7 @@ optional<T> Simulator<T>::GetCurrentWitnessTimeIsolation() const {
const double characteristic_time = 1.0;

// Get the accuracy setting.
const optional<double>& accuracy = get_context().get_accuracy();
const std::optional<double>& accuracy = get_context().get_accuracy();

// Determine the length of the isolation interval.
if (integrator_->get_fixed_step_mode()) {
Expand All @@ -1037,7 +1037,7 @@ optional<T> Simulator<T>::GetCurrentWitnessTimeIsolation() const {
T(iso_scale_factor * accuracy.value() *
integrator_->get_maximum_step_size()));
} else {
return optional<T>();
return std::optional<T>();
}
}

Expand Down Expand Up @@ -1096,7 +1096,7 @@ void Simulator<T>::IsolateWitnessTriggers(
Context<T>& context = get_mutable_context();

// Get the witness isolation interval length.
const optional<T> witness_iso_len = GetCurrentWitnessTimeIsolation();
const std::optional<T> witness_iso_len = GetCurrentWitnessTimeIsolation();

// Check whether witness functions *are* to be isolated. If not, the witnesses
// that were triggered on entry will be the set that is returned.
Expand Down
8 changes: 5 additions & 3 deletions systems/analysis/test/simulator_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -393,7 +393,7 @@ GTEST_TEST(SimulatorTest, VariableStepIsolation) {
// Loop, decreasing accuracy as we go.
while (accuracy > 1e-8) {
// Verify that the isolation window is computed.
optional<double> iso_win = simulator.GetCurrentWitnessTimeIsolation();
std::optional<double> iso_win = simulator.GetCurrentWitnessTimeIsolation();
EXPECT_TRUE(iso_win);

// Verify that the new evaluation is closer to zero than the old one.
Expand Down Expand Up @@ -543,7 +543,8 @@ GTEST_TEST(SimulatorTest, MultipleWitnessesIdentical) {
EXPECT_EQ(w1, w2);

// Verify that they are triggering.
optional<double> iso_time = simulator->GetCurrentWitnessTimeIsolation();
std::optional<double> iso_time =
simulator->GetCurrentWitnessTimeIsolation();
EXPECT_TRUE(iso_time);
EXPECT_LT(std::abs(w1), iso_time.value());

Expand Down Expand Up @@ -600,7 +601,8 @@ GTEST_TEST(SimulatorTest, MultipleWitnessesStaggered) {
simulator.get_mutable_context().SetAccuracy(tol);

// Get the isolation interval tolerance.
const optional<double> iso_tol = simulator.GetCurrentWitnessTimeIsolation();
const std::optional<double> iso_tol =
simulator.GetCurrentWitnessTimeIsolation();
EXPECT_TRUE(iso_tol);

// Simulate to right after the second one should have triggered.
Expand Down
12 changes: 6 additions & 6 deletions systems/framework/context.h
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
#pragma once

#include <memory>
#include <optional>
#include <string>
#include <utility>

#include "drake/common/default_scalars.h"
#include "drake/common/drake_optional.h"
#include "drake/common/drake_throw.h"
#include "drake/common/pointer_cast.h"
#include "drake/common/value.h"
Expand Down Expand Up @@ -179,7 +179,7 @@ class Context : public ContextBase {
/// Returns the accuracy setting (if any). Note that the return type is
/// `optional<double>` rather than the double value itself.
/// @see SetAccuracy() for details.
const optional<double>& get_accuracy() const { return accuracy_; }
const std::optional<double>& get_accuracy() const { return accuracy_; }

/// Returns a const reference to this %Context's parameters.
const Parameters<T>& get_parameters() const { return *parameters_; }
Expand Down Expand Up @@ -532,7 +532,7 @@ class Context : public ContextBase {
/// The common thread among these examples is that they all share the
/// same %Context, so by keeping accuracy here it can be used effectively to
/// control all accuracy-dependent computations.
void SetAccuracy(const optional<double>& accuracy) {
void SetAccuracy(const std::optional<double>& accuracy) {
ThrowIfNotRootContext(__func__, "Accuracy");
const int64_t change_event = this->start_new_change_event();
PropagateAccuracyChange(this, accuracy, change_event);
Expand Down Expand Up @@ -801,7 +801,7 @@ class Context : public ContextBase {
/// (Internal use only) Sets a new accuracy and notifies accuracy-dependent
/// quantities that they are now invalid, as part of a given change event.
static void PropagateAccuracyChange(Context<T>* context,
const optional<double>& accuracy,
const std::optional<double>& accuracy,
int64_t change_event) {
DRAKE_ASSERT(context != nullptr);
context->NoteAccuracyChanged(change_event);
Expand Down Expand Up @@ -861,7 +861,7 @@ class Context : public ContextBase {
/// Invokes PropagateAccuracyChange() on all subcontexts of this Context. The
/// default implementation does nothing, which is suitable for leaf contexts.
/// Diagram contexts must override.
virtual void DoPropagateAccuracyChange(const optional<double>& accuracy,
virtual void DoPropagateAccuracyChange(const std::optional<double>& accuracy,
int64_t change_event) {
unused(accuracy, change_event);
}
Expand Down Expand Up @@ -931,7 +931,7 @@ class Context : public ContextBase {
StepInfo<T> step_info_;

// Accuracy setting.
optional<double> accuracy_;
std::optional<double> accuracy_;

// The parameter values (p) for this Context; this is never null.
copyable_unique_ptr<Parameters<T>> parameters_{
Expand Down
2 changes: 1 addition & 1 deletion systems/framework/diagram_context.h
Original file line number Diff line number Diff line change
Expand Up @@ -467,7 +467,7 @@ class DiagramContext final : public Context<T> {
}

// Recursively sets the accuracy on all subcontexts.
void DoPropagateAccuracyChange(const optional<double>& accuracy,
void DoPropagateAccuracyChange(const std::optional<double>& accuracy,
int64_t change_event) final {
for (auto& subcontext : contexts_) {
DRAKE_ASSERT(subcontext != nullptr);
Expand Down
2 changes: 1 addition & 1 deletion systems/framework/diagram_output_port.h
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
#pragma once

#include <memory>
#include <optional>
#include <string>
#include <utility>

#include "drake/common/default_scalars.h"
#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/drake_optional.h"
#include "drake/common/value.h"
#include "drake/systems/framework/diagram_context.h"
#include "drake/systems/framework/framework_common.h"
Expand Down
4 changes: 2 additions & 2 deletions systems/framework/framework_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,12 @@

#include <algorithm>
#include <memory>
#include <optional>
#include <string>
#include <utility>
#include <vector>

#include "drake/common/drake_assert.h"
#include "drake/common/drake_optional.h"
#include "drake/common/drake_variant.h"
#include "drake/common/type_safe_index.h"
#include "drake/common/value.h"
Expand Down Expand Up @@ -293,7 +293,7 @@ enum BuiltInTicketNumbers {
// of the child's parent Diagram. If the `child_subsystem` index is missing it
// indicates that the prerequisite is internal.
struct OutputPortPrerequisite {
optional<SubsystemIndex> child_subsystem;
std::optional<SubsystemIndex> child_subsystem;
DependencyTicket dependency;
};

Expand Down
4 changes: 2 additions & 2 deletions systems/framework/input_port.h
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
#pragma once

#include <memory>
#include <optional>
#include <string>
#include <type_traits>
#include <utility>

#include "drake/common/constants.h"
#include "drake/common/default_scalars.h"
#include "drake/common/drake_assert.h"
#include "drake/common/drake_optional.h"
#include "drake/common/eigen_types.h"
#include "drake/systems/framework/basic_vector.h"
#include "drake/systems/framework/context.h"
Expand Down Expand Up @@ -184,7 +184,7 @@ class InputPort final : public InputPortBase {
const System<T>* system, internal::SystemMessageInterface* system_base,
std::string name, InputPortIndex index, DependencyTicket ticket,
PortDataType data_type, int size,
const optional<RandomDistribution>& random_type,
const std::optional<RandomDistribution>& random_type,
EvalAbstractCallback eval)
: InputPortBase(system_base, std::move(name), index, ticket, data_type,
size, random_type, std::move(eval)),
Expand Down
2 changes: 1 addition & 1 deletion systems/framework/input_port_base.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ InputPortBase::InputPortBase(
internal::SystemMessageInterface* owning_system, std::string name,
InputPortIndex index, DependencyTicket ticket,
PortDataType data_type, int size,
const optional<RandomDistribution>& random_type,
const std::optional<RandomDistribution>& random_type,
EvalAbstractCallback eval)
: PortBase("Input", owning_system, std::move(name), index, ticket,
data_type, size),
Expand Down
10 changes: 6 additions & 4 deletions systems/framework/input_port_base.h
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
#pragma once

#include <optional>
#include <string>

#include "drake/common/drake_optional.h"
#include "drake/common/random.h"
#include "drake/systems/framework/context_base.h"
#include "drake/systems/framework/framework_common.h"
Expand Down Expand Up @@ -33,7 +33,9 @@ class InputPortBase : public PortBase {
bool is_random() const { return static_cast<bool>(random_type_); }

/** Returns the RandomDistribution if this is a random port. */
optional<RandomDistribution> get_random_type() const { return random_type_; }
std::optional<RandomDistribution> get_random_type() const {
return random_type_;
}

// A using-declaration adds these methods into our class's Doxygen.
// (Placed in an order that makes sense for the class's table of contents.)
Expand Down Expand Up @@ -72,7 +74,7 @@ class InputPortBase : public PortBase {
InputPortBase(
internal::SystemMessageInterface* owning_system, std::string name,
InputPortIndex index, DependencyTicket ticket, PortDataType data_type,
int size, const optional<RandomDistribution>& random_type,
int size, const std::optional<RandomDistribution>& random_type,
EvalAbstractCallback eval);

/** Evaluate this port; throws an exception if the port is not connected. */
Expand All @@ -93,7 +95,7 @@ class InputPortBase : public PortBase {

private:
const EvalAbstractCallback eval_;
const optional<RandomDistribution> random_type_;
const std::optional<RandomDistribution> random_type_;
};

} // namespace systems
Expand Down
2 changes: 1 addition & 1 deletion systems/framework/leaf_output_port.h
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ class LeafOutputPort final : public OutputPort<T> {

// Returns the cache entry's ticket and no subsystem.
internal::OutputPortPrerequisite DoGetPrerequisite() const final {
return {nullopt, cache_entry().ticket()};
return {std::nullopt, cache_entry().ticket()};
};

const CacheEntry* const cache_entry_;
Expand Down
Loading

0 comments on commit 15d1839

Please sign in to comment.