diff --git a/CHANGELOG.md b/CHANGELOG.md index d4f8effbfd..27a676c521 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -16,6 +16,7 @@ * Fixed bug in the representation of SO(2) statespace: [#408](https://github.com/personalrobotics/aikido/pull/408) * Fixed const correctness of StateHandle::getState(): [#419](https://github.com/personalrobotics/aikido/pull/419) * Fixed hidden compose function (in-place version): [#421](https://github.com/personalrobotics/aikido/pull/421) + * Added clone functionality to StateSpace: [#422](https://github.com/personalrobotics/aikido/pull/422) * Constraint diff --git a/include/aikido/statespace/CartesianProduct.hpp b/include/aikido/statespace/CartesianProduct.hpp index 8c09ed9c09..4f9b76e1e8 100644 --- a/include/aikido/statespace/CartesianProduct.hpp +++ b/include/aikido/statespace/CartesianProduct.hpp @@ -35,6 +35,9 @@ class CartesianProduct : public std::enable_shared_from_this, /// \return new \c ScopedState ScopedState createState() const; + /// Creates an identical clone of \c stateIn. + ScopedState cloneState(const StateSpace::State* stateIn) const; + /// Gets number of subspaces. /// /// \return number of subspaces diff --git a/include/aikido/statespace/Rn.hpp b/include/aikido/statespace/Rn.hpp index e31555b9e5..bfb6a5f8fa 100644 --- a/include/aikido/statespace/Rn.hpp +++ b/include/aikido/statespace/Rn.hpp @@ -74,6 +74,9 @@ class R : public virtual StateSpace /// \return new \c ScopedState ScopedState createState() const; + /// Creates an identical clone of \c stateIn. + ScopedState cloneState(const StateSpace::State* stateIn) const; + /// Gets the real vector stored in a \c State. /// /// \param _state a \c State in this state space diff --git a/include/aikido/statespace/SE2.hpp b/include/aikido/statespace/SE2.hpp index 657f126429..2add96084b 100644 --- a/include/aikido/statespace/SE2.hpp +++ b/include/aikido/statespace/SE2.hpp @@ -68,6 +68,9 @@ class SE2 : public virtual StateSpace /// \return new \c ScopedState ScopedState createState() const; + /// Creates an identical clone of \c stateIn. + ScopedState cloneState(const StateSpace::State* stateIn) const; + /// Gets value as an Eigen transformation object. /// /// \param _state a \c State in this state space diff --git a/include/aikido/statespace/SE3.hpp b/include/aikido/statespace/SE3.hpp index 03e20a65cc..d445601848 100644 --- a/include/aikido/statespace/SE3.hpp +++ b/include/aikido/statespace/SE3.hpp @@ -68,6 +68,9 @@ class SE3 : public virtual StateSpace /// \return new \c ScopedState ScopedState createState() const; + /// Creates an identical clone of \c stateIn. + ScopedState cloneState(const StateSpace::State* stateIn) const; + /// Gets value as an Eigen transformation object. /// /// \param _state a \c State in this state space diff --git a/include/aikido/statespace/SO2.hpp b/include/aikido/statespace/SO2.hpp index 1af779e435..bdf396652d 100644 --- a/include/aikido/statespace/SO2.hpp +++ b/include/aikido/statespace/SO2.hpp @@ -36,6 +36,9 @@ class SO2 : virtual public StateSpace /// \return new \c ScopedState. ScopedState createState() const; + /// Creates an identical clone of \c stateIn. + ScopedState cloneState(const StateSpace::State* stateIn) const; + /// Returns state as a rotation angle in (-pi, pi]. /// /// \param[in] state State. diff --git a/include/aikido/statespace/SO3.hpp b/include/aikido/statespace/SO3.hpp index 2f8302a440..4c3490830a 100644 --- a/include/aikido/statespace/SO3.hpp +++ b/include/aikido/statespace/SO3.hpp @@ -66,6 +66,9 @@ class SO3 : virtual public StateSpace /// \return new \c ScopedState ScopedState createState() const; + /// Creates an identical clone of \c stateIn. + ScopedState cloneState(const StateSpace::State* stateIn) const; + /// Gets a state as a unit quaternion. /// /// \param _state input state diff --git a/include/aikido/statespace/ScopedState.hpp b/include/aikido/statespace/ScopedState.hpp index 9ea19b7258..d7f4969fc1 100644 --- a/include/aikido/statespace/ScopedState.hpp +++ b/include/aikido/statespace/ScopedState.hpp @@ -34,6 +34,9 @@ class ScopedState : public _Handle ScopedState(ScopedState&&) = default; ScopedState& operator=(ScopedState&&) = default; + /// Creates an identical clone of the state this ScopedState handles. + ScopedState clone() const; + private: std::unique_ptr mBuffer; }; diff --git a/include/aikido/statespace/StateSpace.hpp b/include/aikido/statespace/StateSpace.hpp index 6b2d8a1fba..f8c0b5024d 100644 --- a/include/aikido/statespace/StateSpace.hpp +++ b/include/aikido/statespace/StateSpace.hpp @@ -47,6 +47,9 @@ class StateSpace /// \return new \c ScopedState ScopedState createState() const; + /// Creates an identical clone of \c stateIn. + ScopedState cloneState(const State* stateIn) const; + /// Allocate a new state. This must be deleted with \c freeState. This is a /// helper function that allocates memory, uses \c allocateStateInBuffer to /// create a \c State, and returns that pointer. diff --git a/include/aikido/statespace/detail/Rn-impl.hpp b/include/aikido/statespace/detail/Rn-impl.hpp index 97a2b10a21..7fdf252eb0 100644 --- a/include/aikido/statespace/detail/Rn-impl.hpp +++ b/include/aikido/statespace/detail/Rn-impl.hpp @@ -121,6 +121,16 @@ auto R::createState() const -> ScopedState return ScopedState(this); } +//============================================================================== +template +auto R::cloneState(const StateSpace::State* stateIn) const -> ScopedState +{ + auto newState = createState(); + copyState(stateIn, newState); + + return newState; +} + //============================================================================== template auto R::getMutableValue(State* _state) const -> Eigen::Map diff --git a/include/aikido/statespace/detail/SO3-impl.hpp b/include/aikido/statespace/detail/SO3-impl.hpp index b5d086b291..55f6c6765b 100644 --- a/include/aikido/statespace/detail/SO3-impl.hpp +++ b/include/aikido/statespace/detail/SO3-impl.hpp @@ -18,6 +18,7 @@ class SO3StateHandle : public statespace::StateHandle /// Construct and initialize to \c nullptr. SO3StateHandle() { + // Do nothing } /// Construct a handle for \c _state in \c _space. @@ -27,6 +28,7 @@ class SO3StateHandle : public statespace::StateHandle SO3StateHandle(const StateSpace* _space, QualifiedState* _state) : statespace::StateHandle(_space, _state) { + // Do nothing } /// Constructs a point in SO(3) from a unit quaternion. diff --git a/include/aikido/statespace/detail/ScopedState-impl.hpp b/include/aikido/statespace/detail/ScopedState-impl.hpp index 5d6a7c263b..a893c9fbfd 100644 --- a/include/aikido/statespace/detail/ScopedState-impl.hpp +++ b/include/aikido/statespace/detail/ScopedState-impl.hpp @@ -20,5 +20,12 @@ ScopedState::~ScopedState() this->mSpace->freeStateInBuffer(this->mState); } +//============================================================================== +template +ScopedState ScopedState::clone() const +{ + return this->mSpace->cloneState(this->mState); +} + } // namespace statespace } // namespace aikido diff --git a/src/statespace/CartesianProduct.cpp b/src/statespace/CartesianProduct.cpp index 48d2d1f4f8..51b4cf013d 100644 --- a/src/statespace/CartesianProduct.cpp +++ b/src/statespace/CartesianProduct.cpp @@ -31,6 +31,16 @@ auto CartesianProduct::createState() const -> ScopedState return ScopedState(this); } +//============================================================================== +CartesianProduct::ScopedState CartesianProduct::cloneState( + const StateSpace::State* stateIn) const +{ + auto newState = createState(); + copyState(stateIn, newState); + + return newState; +} + //============================================================================== std::size_t CartesianProduct::getNumSubspaces() const { diff --git a/src/statespace/SE2.cpp b/src/statespace/SE2.cpp index a617ad04ff..ebc954cf23 100644 --- a/src/statespace/SE2.cpp +++ b/src/statespace/SE2.cpp @@ -31,6 +31,15 @@ auto SE2::createState() const -> ScopedState return ScopedState(this); } +//============================================================================== +SE2::ScopedState SE2::cloneState(const StateSpace::State* stateIn) const +{ + auto newState = createState(); + copyState(stateIn, newState); + + return newState; +} + //============================================================================== auto SE2::getIsometry(const State* _state) const -> const Isometry2d& { diff --git a/src/statespace/SE3.cpp b/src/statespace/SE3.cpp index bf759dd62e..6934cfb11a 100644 --- a/src/statespace/SE3.cpp +++ b/src/statespace/SE3.cpp @@ -31,6 +31,15 @@ auto SE3::createState() const -> ScopedState return ScopedState(this); } +//============================================================================== +SE3::ScopedState SE3::cloneState(const StateSpace::State* stateIn) const +{ + auto newState = createState(); + copyState(stateIn, newState); + + return newState; +} + //============================================================================== auto SE3::getIsometry(const State* _state) const -> const Isometry3d& { diff --git a/src/statespace/SO2.cpp b/src/statespace/SO2.cpp index fb7c7bb622..1383883199 100644 --- a/src/statespace/SO2.cpp +++ b/src/statespace/SO2.cpp @@ -1,7 +1,8 @@ -#include +#include "aikido/statespace/SO2.hpp" namespace aikido { namespace statespace { + //============================================================================== SO2::State::State(double angle) { @@ -43,6 +44,15 @@ auto SO2::createState() const -> ScopedState return ScopedState(this); } +//============================================================================== +SO2::ScopedState SO2::cloneState(const StateSpace::State* stateIn) const +{ + auto newState = createState(); + copyState(stateIn, newState); + + return newState; +} + //============================================================================== double SO2::toAngle(const State* state) const { diff --git a/src/statespace/SO3.cpp b/src/statespace/SO3.cpp index ca923e3f12..c0b22e9afc 100644 --- a/src/statespace/SO3.cpp +++ b/src/statespace/SO3.cpp @@ -34,6 +34,15 @@ auto SO3::createState() const -> ScopedState return ScopedState(this); } +//============================================================================== +auto SO3::cloneState(const StateSpace::State* stateIn) const -> ScopedState +{ + auto newState = createState(); + copyState(stateIn, newState); + + return newState; +} + //============================================================================== auto SO3::getQuaternion(const State* _state) const -> const Quaternion& { diff --git a/src/statespace/StateSpace.cpp b/src/statespace/StateSpace.cpp index 02422de9c6..2391e818fd 100644 --- a/src/statespace/StateSpace.cpp +++ b/src/statespace/StateSpace.cpp @@ -9,6 +9,16 @@ auto StateSpace::createState() const -> ScopedState return ScopedState(this); } +//============================================================================== +StateSpace::ScopedState StateSpace::cloneState( + const StateSpace::State* stateIn) const +{ + auto newState = createState(); + copyState(stateIn, newState); + + return newState; +} + //============================================================================== void StateSpace::compose(State* _state1, const State* _state2) const { diff --git a/tests/statespace/test_CartesianProduct.cpp b/tests/statespace/test_CartesianProduct.cpp index 093018a750..38fa64614d 100644 --- a/tests/statespace/test_CartesianProduct.cpp +++ b/tests/statespace/test_CartesianProduct.cpp @@ -1,3 +1,4 @@ +#include #include #include #include @@ -12,6 +13,28 @@ using aikido::statespace::SO2; using aikido::statespace::SO3; using aikido::statespace::SE2; +TEST(CartesianProduct, Clone) +{ + CartesianProduct space({std::make_shared(), std::make_shared()}); + + for (auto i = 0u; i < 5u; ++i) + { + auto s1 = space.createState(); + const auto angle = dart::math::random(-M_PI, M_PI); + s1.getSubStateHandle(0).fromAngle(angle); + s1.getSubStateHandle(1).setValue(Eigen::Vector2d::Random()); + + auto s2 = s1.clone(); + + EXPECT_DOUBLE_EQ( + s1.getSubStateHandle(0).toAngle(), + s2.getSubStateHandle(0).toAngle()); + EXPECT_TRUE( + s1.getSubStateHandle(1).getValue().isApprox( + s2.getSubStateHandle(1).getValue())); + } +} + TEST(CartesianProduct, Compose) { using Eigen::Vector2d; diff --git a/tests/statespace/test_Rn.cpp b/tests/statespace/test_Rn.cpp index f19652a8bd..47af7dee4f 100644 --- a/tests/statespace/test_Rn.cpp +++ b/tests/statespace/test_Rn.cpp @@ -5,6 +5,42 @@ using aikido::statespace::Rn; using aikido::statespace::R3; using R4 = aikido::statespace::R<4>; +//============================================================================== +TEST(Rn, CloneR3) +{ + R3 rvss; + + for (auto i = 0u; i < 5u; ++i) + { + const Eigen::Vector3d pos = Eigen::Vector3d::Random(); + + auto s1 = rvss.createState(); + s1.setValue(pos); + + auto s2 = s1.clone(); + + EXPECT_TRUE(s1.getValue().isApprox(s2.getValue())); + } +} + +//============================================================================== +TEST(Rn, CloneRx) +{ + Rn rvss(3); + + for (auto i = 0u; i < 5u; ++i) + { + const Eigen::Vector3d pos = Eigen::Vector3d::Random(); + + auto s1 = rvss.createState(); + s1.setValue(pos); + + auto s2 = s1.clone(); + + EXPECT_TRUE(s1.getValue().isApprox(s2.getValue())); + } +} + //============================================================================== TEST(Rn, ComposeR3) { diff --git a/tests/statespace/test_SE2.cpp b/tests/statespace/test_SE2.cpp index 058ec8880e..04b5f66f6f 100644 --- a/tests/statespace/test_SE2.cpp +++ b/tests/statespace/test_SE2.cpp @@ -1,8 +1,29 @@ +#include #include #include using aikido::statespace::SE2; +TEST(SE2, Clone) +{ + SE2 se2; + + for (auto i = 0u; i < 5u; ++i) + { + const auto angle = dart::math::random(-M_PI, M_PI); + Eigen::Isometry2d pose = Eigen::Isometry2d::Identity(); + pose.rotate(Eigen::Rotation2Dd(angle)); + pose.translation() = Eigen::Vector2d::Random(); + + auto s1 = se2.createState(); + s1.setIsometry(pose); + + auto s2 = s1.clone(); + + EXPECT_TRUE(s1.getIsometry().isApprox(s2.getIsometry())); + } +} + TEST(SE2, Compose) { SE2 space; diff --git a/tests/statespace/test_SE3.cpp b/tests/statespace/test_SE3.cpp index 7a6b848356..4405112520 100644 --- a/tests/statespace/test_SE3.cpp +++ b/tests/statespace/test_SE3.cpp @@ -1,9 +1,32 @@ +#include #include #include using aikido::statespace::SE3; using Vector6d = Eigen::Matrix; +TEST(SE3, Clone) +{ + SE3 se3; + + for (auto i = 0u; i < 5u; ++i) + { + Eigen::Isometry3d pose = Eigen::Isometry3d::Identity(); + const auto angle = dart::math::random(-M_PI, M_PI); + const auto axis = Eigen::Vector3d::Random().normalized(); + const auto angleAxis = Eigen::AngleAxisd(angle, axis); + pose.linear() = angleAxis.toRotationMatrix(); + pose.translation() = Eigen::Vector3d::Random(); + + auto s1 = se3.createState(); + s1.setIsometry(pose); + + auto s2 = s1.clone(); + + EXPECT_TRUE(s1.getIsometry().isApprox(s2.getIsometry())); + } +} + TEST(SE3, Compose) { SE3 space; diff --git a/tests/statespace/test_SO2.cpp b/tests/statespace/test_SO2.cpp index 05f886b71f..f69ab2ae97 100644 --- a/tests/statespace/test_SO2.cpp +++ b/tests/statespace/test_SO2.cpp @@ -1,3 +1,4 @@ +#include #include #include #include "eigen_tests.hpp" @@ -26,6 +27,23 @@ TEST(SO2, CornerCasePositive) EXPECT_DOUBLE_EQ(s1.toAngle(), M_PI); } +TEST(SO2, Clone) +{ + SO2 so2; + + for (auto i = 0u; i < 5u; ++i) + { + const auto angle = dart::math::random(-M_PI, M_PI); + + auto s1 = so2.createState(); + s1.fromAngle(angle); + + auto s2 = s1.clone(); + + EXPECT_DOUBLE_EQ(s1.toAngle(), s2.toAngle()); + } +} + TEST(SO2, ComposeThrowsOnAliasing) { SO2::State s1(M_PI_4); diff --git a/tests/statespace/test_SO3.cpp b/tests/statespace/test_SO3.cpp index 896d404e50..0588c4ade1 100644 --- a/tests/statespace/test_SO3.cpp +++ b/tests/statespace/test_SO3.cpp @@ -1,8 +1,29 @@ +#include #include #include using aikido::statespace::SO3; +TEST(SO3, Clone) +{ + SO3 so3; + + for (auto i = 0u; i < 5u; ++i) + { + const auto angle = dart::math::random(-M_PI, M_PI); + const auto axis = Eigen::Vector3d::Random().normalized(); + const auto angleAxis = Eigen::AngleAxisd(angle, axis); + const Eigen::Quaterniond quat(angleAxis); + + auto s1 = so3.createState(); + s1.setQuaternion(quat); + + auto s2 = s1.clone(); + + EXPECT_TRUE(s1.getQuaternion().isApprox(s2.getQuaternion())); + } +} + TEST(SO3, Compose) { SO3::State identity;