Skip to content

Commit

Permalink
Remove use of boost::optional
Browse files Browse the repository at this point in the history
  • Loading branch information
jslee02 committed Jan 14, 2022
1 parent be24fe9 commit 9f5de78
Show file tree
Hide file tree
Showing 19 changed files with 59 additions and 64 deletions.
15 changes: 5 additions & 10 deletions dart/common/Optional.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,22 +33,17 @@
#ifndef DART_COMMON_OPTIONAL_HPP_
#define DART_COMMON_OPTIONAL_HPP_

#if __cplusplus >= 201703L
#include <optional>
#else
#include <boost/optional.hpp>
#endif
#include <optional>

#include "dart/common/Deprecated.hpp"

namespace dart {
namespace common {

#if __cplusplus >= 201703L
/// \deprecated Use std::optional instead
template <class T>
DART_DEPRECATED(6.13)
using optional = std::optional<T>;
#else
template <class T>
using optional = boost::optional<T>;
#endif

} // namespace common
} // namespace dart
Expand Down
2 changes: 1 addition & 1 deletion dart/utils/mjcf/detail/Body.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ namespace detail {
//==============================================================================
Errors Body::read(
tinyxml2::XMLElement* element,
const common::optional<Size>& size,
const std::optional<Size>& size,
const Defaults& defaults,
const Default* currentDefault)
{
Expand Down
2 changes: 1 addition & 1 deletion dart/utils/mjcf/detail/Body.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ class Body final
friend class Worldbody;
Errors read(
tinyxml2::XMLElement* element,
const common::optional<Size>& size,
const std::optional<Size>& size,
const Defaults& defaults,
const Default* currentDefault);

Expand Down
2 changes: 1 addition & 1 deletion dart/utils/mjcf/detail/BodyAttributes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace detail {
Errors appendBodyAttributes(
BodyAttributes& attributes,
tinyxml2::XMLElement* element,
const common::optional<Size>& size)
const std::optional<Size>& size)
{
Errors errors;

Expand Down
18 changes: 9 additions & 9 deletions dart/utils/mjcf/detail/BodyAttributes.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,52 +55,52 @@ class Size;
struct BodyAttributes final
{
/// Name of the body.
common::optional<std::string> mName;
std::optional<std::string> mName;

/// If this attribute is present, all descendant elements that admit a
/// defaults class will use the class specified here, unless they specify
/// their own class or another body with a childclass attribute is
/// encountered along the chain of nested bodies.
common::optional<std::string> mChildClass;
std::optional<std::string> mChildClass;

/// If this attribute is "true", the body is labeled as a mocap body.
bool mMocap{false};

/// The 3D position of the body frame, in local or global coordinates as
/// determined by the coordinate attribute of compiler.
common::optional<Eigen::Vector3d> mPos;
std::optional<Eigen::Vector3d> mPos;

/// Quaternion
Eigen::Quaterniond mQuat{Eigen::Quaterniond::Identity()};

/// These are the quantities (x, y, z, a) mentioned above. The last number
/// is the angle of rotation, in degrees or radians as specified by the
/// angle attribute of compiler.
common::optional<Eigen::Vector4d> mAxisAngle;
std::optional<Eigen::Vector4d> mAxisAngle;

/// Rotation angles around three coordinate axes. The sequence of axes
/// around which these rotations are applied is determined by the eulerseq
/// attribute of compiler and is the same for the entire model.
common::optional<Eigen::Vector3d> mEuler;
std::optional<Eigen::Vector3d> mEuler;

/// The first 3 numbers are the X axis of the frame. The next 3 numbers are
/// the Y axis of the frame, which is automatically made orthogonal to the X
/// axis. The Z axis is then defined as the cross-product of the X and Y
/// axes.
common::optional<Eigen::Vector6d> mXYAxes;
std::optional<Eigen::Vector6d> mXYAxes;

/// The Z axis of the frame
common::optional<Eigen::Vector3d> mZAxis;
std::optional<Eigen::Vector3d> mZAxis;

Eigen::VectorXd mUser;

common::optional<Inertial> mInertial;
std::optional<Inertial> mInertial;
};

Errors appendBodyAttributes(
BodyAttributes& attributes,
tinyxml2::XMLElement* element,
const common::optional<Size>& size);
const std::optional<Size>& size);

} // namespace detail
} // namespace MjcfParser
Expand Down
2 changes: 1 addition & 1 deletion dart/utils/mjcf/detail/Geom.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ Errors Geom::read(

//==============================================================================
static bool canUseFromTo(
GeomType type, const common::optional<Eigen::Vector6d>& fromto)
GeomType type, const std::optional<Eigen::Vector6d>& fromto)
{
if (!fromto)
return false;
Expand Down
18 changes: 9 additions & 9 deletions dart/utils/mjcf/detail/GeomAttributes.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ namespace detail {
struct GeomAttributes final
{
/// Name of the geom
common::optional<std::string> mName;
std::optional<std::string> mName;

/// Type of geometric shape
GeomType mType{GeomType::SPHERE};
Expand All @@ -74,7 +74,7 @@ struct GeomAttributes final
Eigen::Vector3d mFriction{Eigen::Vector3d(1, 0.005, 0.0001)};

/// Mass
common::optional<double> mMass;
std::optional<double> mMass;

/// Material density used to compute the geom mass and inertia.
double mDensity{1000};
Expand All @@ -95,7 +95,7 @@ struct GeomAttributes final
/// This attribute can only be used with capsule, cylinder, ellipsoid and
/// box geoms. It provides an alternative specification of the geom length
/// as well as the frame position and orientation.
common::optional<Eigen::Vector6d> mFromTo;
std::optional<Eigen::Vector6d> mFromTo;

/// Position of the geom frame, in local or global coordinates as determined
/// by the coordinate attribute of compiler.
Expand All @@ -107,23 +107,23 @@ struct GeomAttributes final
/// These are the quantities (x, y, z, a) mentioned above. The last number
/// is the angle of rotation, in degrees or radians as specified by the
/// angle attribute of compiler.
common::optional<Eigen::Vector4d> mAxisAngle;
std::optional<Eigen::Vector4d> mAxisAngle;

/// Rotation angles around three coordinate axes.
common::optional<Eigen::Vector3d> mEuler;
std::optional<Eigen::Vector3d> mEuler;

/// The first 3 numbers are the X axis of the frame. The next 3 numbers are
/// the Y axis of the frame, which is automatically made orthogonal to the X
/// axis. The Z axis is then defined as the cross-product of the X and Y
/// axes.
common::optional<Eigen::Vector6d> mXYAxes;
std::optional<Eigen::Vector6d> mXYAxes;

/// The Z axis of the frame
common::optional<Eigen::Vector3d> mZAxis;
std::optional<Eigen::Vector3d> mZAxis;

common::optional<std::string> mHField;
std::optional<std::string> mHField;

common::optional<std::string> mMesh;
std::optional<std::string> mMesh;

double mFitScale{1};
};
Expand Down
12 changes: 6 additions & 6 deletions dart/utils/mjcf/detail/Inertial.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,19 +86,19 @@ class Inertial final
/// These are the quantities (x, y, z, a) mentioned above. The last number
/// is the angle of rotation, in degrees or radians as specified by the
/// angle attribute of compiler.
common::optional<Eigen::Vector4d> mAxisAngle;
std::optional<Eigen::Vector4d> mAxisAngle;

/// Rotation angles around three coordinate axes.
common::optional<Eigen::Vector3d> mEuler;
std::optional<Eigen::Vector3d> mEuler;

/// The first 3 numbers are the X axis of the frame. The next 3 numbers are
/// the Y axis of the frame, which is automatically made orthogonal to the X
/// axis. The Z axis is then defined as the cross-product of the X and Y
/// axes.
common::optional<Eigen::Vector6d> mXYAxes;
std::optional<Eigen::Vector6d> mXYAxes;

/// The Z axis of the frame
common::optional<Eigen::Vector3d> mZAxis;
std::optional<Eigen::Vector3d> mZAxis;

Eigen::Isometry3d mRelativeTransform{Eigen::Isometry3d::Identity()};
Eigen::Isometry3d mWorldTransform{Eigen::Isometry3d::Identity()};
Expand All @@ -108,10 +108,10 @@ class Inertial final

/// Diagonal inertia matrix, expressing the body inertia relative to the
/// inertial frame.
common::optional<Eigen::Vector3d> mDiagInertia;
std::optional<Eigen::Vector3d> mDiagInertia;

/// Full inertia matrix M.
common::optional<Eigen::Vector6d> mFullInertia;
std::optional<Eigen::Vector6d> mFullInertia;
};

Data mData;
Expand Down
2 changes: 1 addition & 1 deletion dart/utils/mjcf/detail/JointAttributes.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ namespace detail {

struct JointAttributes final
{
common::optional<std::string> mName;
std::optional<std::string> mName;

JointType mType{JointType::HINGE};

Expand Down
4 changes: 2 additions & 2 deletions dart/utils/mjcf/detail/MeshAttributes.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,9 @@ namespace detail {
struct MeshAttributes final
{
/// Name of the Asset
common::optional<std::string> mName;
std::optional<std::string> mName;

common::optional<std::string> mFile;
std::optional<std::string> mFile;

Eigen::Vector3d mScale{Eigen::Vector3d::Ones()};
};
Expand Down
2 changes: 1 addition & 1 deletion dart/utils/mjcf/detail/Site.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,7 @@ Errors Site::read(tinyxml2::XMLElement* element)

//==============================================================================
static bool canUseFromTo(
GeomType type, const common::optional<Eigen::Vector6d>& fromto)
GeomType type, const std::optional<Eigen::Vector6d>& fromto)
{
if (!fromto)
return false;
Expand Down
12 changes: 6 additions & 6 deletions dart/utils/mjcf/detail/Site.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ class Site final
struct Data
{
/// Name of the Site
common::optional<std::string> mName;
std::optional<std::string> mName;

/// Type of Siteetric shape
GeomType mType{GeomType::SPHERE};
Expand All @@ -131,7 +131,7 @@ class Site final
/// This attribute can only be used with capsule, cylinder, ellipsoid and
/// box Sites. It provides an alternative specification of the Site length
/// as well as the frame position and orientation.
common::optional<Eigen::Vector6d> mFromTo;
std::optional<Eigen::Vector6d> mFromTo;

/// Position of the Site frame, in local or global coordinates as determined
/// by the coordinate attribute of compiler.
Expand All @@ -143,19 +143,19 @@ class Site final
/// These are the quantities (x, y, z, a) mentioned above. The last number
/// is the angle of rotation, in degrees or radians as specified by the
/// angle attribute of compiler.
common::optional<Eigen::Vector4d> mAxisAngle;
std::optional<Eigen::Vector4d> mAxisAngle;

/// Rotation angles around three coordinate axes.
common::optional<Eigen::Vector3d> mEuler;
std::optional<Eigen::Vector3d> mEuler;

/// The first 3 numbers are the X axis of the frame. The next 3 numbers are
/// the Y axis of the frame, which is automatically made orthogonal to the X
/// axis. The Z axis is then defined as the cross-product of the X and Y
/// axes.
common::optional<Eigen::Vector6d> mXYAxes;
std::optional<Eigen::Vector6d> mXYAxes;

/// The Z axis of the frame
common::optional<Eigen::Vector3d> mZAxis;
std::optional<Eigen::Vector3d> mZAxis;
};

Data mData;
Expand Down
8 changes: 4 additions & 4 deletions dart/utils/mjcf/detail/Utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,10 +101,10 @@ Errors checkOrientationValidity(const tinyxml2::XMLElement* element)
//==============================================================================
Eigen::Matrix3d compileRotation(
const Eigen::Quaterniond& quat,
const common::optional<Eigen::Vector4d>& axisAngle,
const common::optional<Eigen::Vector3d>& euler,
const common::optional<Eigen::Vector6d>& xyAxes,
const common::optional<Eigen::Vector3d>& zAxis,
const std::optional<Eigen::Vector4d>& axisAngle,
const std::optional<Eigen::Vector3d>& euler,
const std::optional<Eigen::Vector6d>& xyAxes,
const std::optional<Eigen::Vector3d>& zAxis,
const Compiler& compiler)
{
Eigen::Matrix3d rot = Eigen::Matrix3d::Identity();
Expand Down
8 changes: 4 additions & 4 deletions dart/utils/mjcf/detail/Utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,10 +54,10 @@ Errors checkOrientationValidity(const tinyxml2::XMLElement* element);
/// compiler settings
Eigen::Matrix3d compileRotation(
const Eigen::Quaterniond& quat,
const common::optional<Eigen::Vector4d>& axisAngle,
const common::optional<Eigen::Vector3d>& euler,
const common::optional<Eigen::Vector6d>& xyAxes,
const common::optional<Eigen::Vector3d>& zAxis,
const std::optional<Eigen::Vector4d>& axisAngle,
const std::optional<Eigen::Vector3d>& euler,
const std::optional<Eigen::Vector6d>& xyAxes,
const std::optional<Eigen::Vector3d>& zAxis,
const Compiler& compiler);

/// Includes other MJCF model file into \c element
Expand Down
2 changes: 1 addition & 1 deletion dart/utils/mjcf/detail/Weld.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ const std::string& Weld::getBody2() const
}

//==============================================================================
const common::optional<Eigen::Isometry3d>& Weld::getRelativeTransform() const
const std::optional<Eigen::Isometry3d>& Weld::getRelativeTransform() const
{
return mRelativeTransfrom;
}
Expand Down
4 changes: 2 additions & 2 deletions dart/utils/mjcf/detail/Weld.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class Weld final
const Eigen::Matrix<double, 5, 1>& getSolImp() const;
const std::string& getBody1() const;
const std::string& getBody2() const;
const common::optional<Eigen::Isometry3d>& getRelativeTransform() const;
const std::optional<Eigen::Isometry3d>& getRelativeTransform() const;

private:
// Private memebers used by MujocoModel class
Expand All @@ -73,7 +73,7 @@ class Weld final
std::string mBody2;
bool mUsePredefinedRelativeTransform{true};
// Relative transform from body1 to body2
common::optional<Eigen::Isometry3d> mRelativeTransfrom;
std::optional<Eigen::Isometry3d> mRelativeTransfrom;
};

} // namespace detail
Expand Down
4 changes: 2 additions & 2 deletions dart/utils/mjcf/detail/WeldAttributes.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,12 +46,12 @@ namespace detail {

struct WeldAttributes final
{
common::optional<std::string> mName;
std::optional<std::string> mName;
bool mActive{true};
Eigen::Vector2d mSolRef;
Eigen::Matrix<double, 5, 1> mSolImp;
std::string mBody1;
common::optional<std::string> mBody2;
std::optional<std::string> mBody2;
Eigen::Matrix<double, 7, 1> mRelPose;

WeldAttributes();
Expand Down
2 changes: 1 addition & 1 deletion dart/utils/mjcf/detail/Worldbody.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace detail {
//==============================================================================
Errors Worldbody::read(
tinyxml2::XMLElement* element,
const common::optional<Size>& size,
const std::optional<Size>& size,
const Defaults& defaults,
const Default* currentDefault,
const common::Uri& baseUri,
Expand Down
4 changes: 2 additions & 2 deletions dart/utils/mjcf/detail/Worldbody.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ class Worldbody final
friend class MujocoModel;
Errors read(
tinyxml2::XMLElement* element,
const common::optional<Size>& size,
const std::optional<Size>& size,
const Defaults& defaults,
const Default* currentDefault,
const common::Uri& baseUri,
Expand All @@ -96,7 +96,7 @@ class Worldbody final
Errors postprocess(const Compiler& compiler);

private:
common::optional<std::string> mChildClass;
std::optional<std::string> mChildClass;
std::vector<Geom> mGeoms;
std::vector<Site> mSites;
std::vector<Body> mRootBodies;
Expand Down

0 comments on commit 9f5de78

Please sign in to comment.