Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix geodesic for SO(2) #408

Merged
merged 25 commits into from
May 17, 2018
Merged
Show file tree
Hide file tree
Changes from 16 commits
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
8d6485d
restrict so2 between -pi to pi + cleanup
aditya-vk May 10, 2018
83d885a
make format
aditya-vk May 10, 2018
eaae064
WIP: changes in progress
aditya-vk May 10, 2018
d56674f
proposal complete
aditya-vk May 10, 2018
75b8ee3
Merge branch 'master' into bugfix/avk/so2
aditya-vk May 10, 2018
4e80b34
Merge branch 'master' into bugfix/avk/so2
jslee02 May 11, 2018
bc9eaae
cascade updates to function names
aditya-vk May 11, 2018
94971e5
test the new changes to SO2 space
aditya-vk May 11, 2018
2aaaf18
cascade update of change in function names
aditya-vk May 11, 2018
413e4c6
make format
aditya-vk May 11, 2018
c065eaa
corrections in test_SO2
aditya-vk May 11, 2018
0ddd98b
correct test_SO2Angular
aditya-vk May 11, 2018
b8106f7
make format
aditya-vk May 11, 2018
45bd5a3
remove unnecessary code block
aditya-vk May 11, 2018
e49ce19
correct test in test_metaSkeletonStateSpace
aditya-vk May 12, 2018
9329c6f
Merge branch 'master' into bugfix/avk/so2
gilwoolee May 12, 2018
c75fbe8
Merge branch 'master' into bugfix/avk/so2
jslee02 May 14, 2018
8de5b8f
address JS's comments
aditya-vk May 14, 2018
bc60aa3
Merge branch 'master' into bugfix/avk/so2
jslee02 May 15, 2018
847f1a3
address Gilwoo's comments
aditya-vk May 15, 2018
e41999f
Merge remote into local
aditya-vk May 15, 2018
17d044e
add tests for when functions throw
aditya-vk May 15, 2018
fa5d475
update log
aditya-vk May 16, 2018
91556bf
Merge branch 'master' into bugfix/avk/so2
jslee02 May 17, 2018
3daa903
Fix incorrect merging of previous commit
jslee02 May 17, 2018
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
129 changes: 61 additions & 68 deletions include/aikido/statespace/SO2.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,44 +18,7 @@ class SO2 : virtual public StateSpace
{
public:
/// State in SO(2), a planar rotation.
class State : public StateSpace::State
{
public:
/// Constructs the identity element.
State();

~State() = default;

/// Constructs a state from a rotation angle.
///
/// \param _angle rotation angle
explicit State(double _angle);

/// Gets state as a rotation angle.
///
/// \return rotation angle
double getAngle() const;

/// Sets state to a rotation angle.
///
/// \param _angle rotation angle
void setAngle(double _angle);

/// Gets state as an Eigen transformation.
///
/// \return Eigen transformation
Eigen::Rotation2Dd getRotation() const;

/// Sets state it an Eigen transformation.
///
/// \param _rotation Eigen transformation
void setRotation(const Eigen::Rotation2Dd& _rotation);

private:
double mAngle;

friend class SO2;
};
class State;

using StateHandle = SO2StateHandle<State>;
using StateHandleConst = SO2StateHandle<const State>;
Expand All @@ -71,78 +34,108 @@ class SO2 : virtual public StateSpace
/// \return new \c ScopedState
ScopedState createState() const;

/// Gets state as a rotation angle.
/// Returns state as a rotation angle.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nit: Let's describe the return angle is in the range of (-pi, pi].

///
/// \param _state input state
/// \return rotation angle
double getAngle(const State* _state) const;
/// \param[in] state State.
double toAngle(const State* state) const;

/// Sets state to a rotation angle.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nit: Let's update the description something like "Sets state from a rotation angle.".

///
/// \param _state input state
/// \param _angle rotation angle
void setAngle(State* _state, double _angle) const;
/// \param[in] angle Rotation angle.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can we specify the range for angle here? (If it allows (-inf, inf), mention that)

/// \param[out] state State corresponding to angle
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nit: Let's order the argument docstring as the corresponding arguments are ordered.

void fromAngle(State* state, double angle) const;

/// Gets state as an Eigen transformation.
/// Returns state as an Eigen transformation.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nit: Eigen rotation.?

///
/// \param _state input state
/// \return Eigen transformation
Eigen::Rotation2Dd getRotation(const State* _state) const;
/// \param[in] state State
Eigen::Rotation2Dd toRotation(const State* state) const;

/// Sets state it an Eigen transformation.
///
/// \param _state input state
/// \param _rotation Eigen transformation
void setRotation(State* _state, const Eigen::Rotation2Dd& _rotation) const;
/// \param[in] rotation Eigen transformation.
/// \param[out] state State corresponding to rotation.
void fromRotation(State* state, const Eigen::Rotation2Dd& rotation) const;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Let's order the docstring as the argument listed.


// Documentation inherited.
std::size_t getStateSizeInBytes() const override;

// Documentation inherited.
StateSpace::State* allocateStateInBuffer(void* _buffer) const override;
StateSpace::State* allocateStateInBuffer(void* buffer) const override;

// Documentation inherited.
void freeStateInBuffer(StateSpace::State* _state) const override;
void freeStateInBuffer(StateSpace::State* state) const override;

// Documentation inherited.
void compose(
const StateSpace::State* _state1,
const StateSpace::State* _state2,
StateSpace::State* _out) const override;
const StateSpace::State* state1,
const StateSpace::State* state2,
StateSpace::State* out) const override;

// Documentation inherited.
void getIdentity(StateSpace::State* _out) const override;
void getIdentity(StateSpace::State* out) const override;

// Documentation inherited.
void getInverse(
const StateSpace::State* _in, StateSpace::State* _out) const override;
const StateSpace::State* in, StateSpace::State* out) const override;

// Documentation inherited.
std::size_t getDimension() const override;

// Documentation inherited.
void copyState(
const StateSpace::State* _source,
StateSpace::State* _destination) const override;
const StateSpace::State* source,
StateSpace::State* destination) const override;

/// Exponential mapping of Lie algebra element to a Lie group element. The
/// tangent space is parameterized a rotation angle.
///
/// \param _tangent element of the tangent space
/// \param[out] _out corresponding element of the Lie group
/// \param[in] tangent Element of the tangent space
/// \param[out] out Corresponding element of the Lie group
void expMap(
const Eigen::VectorXd& _tangent, StateSpace::State* _out) const override;
const Eigen::VectorXd& tangent, StateSpace::State* out) const override;

/// Log mapping of Lie group element to a Lie algebra element. The tangent
/// space is parameterized as a rotation angle.
///
/// \param _in element of this Lie group
/// \param[out] _tangent corresponding element of the tangent space
/// \param[in] in Element of this Lie group
/// \param[out] tangent Corresponding element of the tangent space
void logMap(
const StateSpace::State* _in, Eigen::VectorXd& _tangent) const override;
const StateSpace::State* in, Eigen::VectorXd& tangent) const override;

/// Print the angle represented by the state
void print(const StateSpace::State* _state, std::ostream& _os) const override;
void print(const StateSpace::State* state, std::ostream& os) const override;
};

class SO2::State : public StateSpace::State
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It seems SO2::State won't be inherited. Let's mark this class as final.

{
public:
/// Constructs a state from a rotation angle.
///
/// \param[in] angle Rotation angle
explicit State(double angle = 0.0);

~State() = default;

/// Returns state as a rotation angle.
double toAngle() const;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nit: Let's inform that the range of the return angle.


/// Sets state to a rotation angle.
///
/// \param[in] angle Rotation angle
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same as above, specify the range for angle.

void fromAngle(double angle);

/// Returns state as an Eigen transformation.
Eigen::Rotation2Dd toRotation() const;

/// Sets state given an Eigen transformation.
///
/// \param[in] rotation Eigen transformation
void fromRotation(const Eigen::Rotation2Dd& rotation);

private:
double mAngle;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nit: Please add docstring.


friend class SO2;
};

} // namespace statespace
Expand Down
32 changes: 14 additions & 18 deletions include/aikido/statespace/detail/SO2-impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,36 +27,32 @@ class SO2StateHandle : public statespace::StateHandle<SO2, _QualifiedState>
{
}

/// Gets state as a rotation angle.
///
/// \return rotation angle
double getAngle() const
/// Returns angle corresponding to the state.
double toAngle() const
{
return this->getStateSpace()->getAngle(this->getState());
return this->getStateSpace()->toAngle(this->getState());
}

/// Sets state to a rotation angle.
/// Sets state given a rotation angle.
///
/// \param _angle rotation angle
void setAngle(double _angle)
/// \param[in] angle rotation angle.
void fromAngle(double angle)
{
return this->getStateSpace()->setAngle(this->getState(), _angle);
return this->getStateSpace()->fromAngle(this->getState(), angle);
}

/// Gets state as an Eigen transformation.
///
/// \return Eigen transformation
Eigen::Rotation2Dd getRotation() const
/// Returns the Eigen transformation corresponding to state.
Eigen::Rotation2Dd toRotation() const
{
return this->getStateSpace()->getRotation(this->getState());
return this->getStateSpace()->toRotation(this->getState());
}

/// Sets state it an Eigen transformation.
/// Sets state given an Eigen transformation.
///
/// \param _rotation Eigen transformation
void setRotation(const Eigen::Rotation2Dd& _rotation)
/// \param[in] rotation Eigen transformation.
void fromRotation(const Eigen::Rotation2Dd& rotation)
{
return this->getStateSpace()->setRotation(this->getState(), _rotation);
return this->getStateSpace()->fromRotation(this->getState(), rotation);
}
};

Expand Down
2 changes: 1 addition & 1 deletion src/constraint/uniform/SO2UniformSampler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ statespace::StateSpacePtr SO2UniformSampleGenerator::getStateSpace() const
bool SO2UniformSampleGenerator::sample(statespace::StateSpace::State* _state)
{
const double angle = mDistribution(*mRng);
mSpace->setAngle(static_cast<statespace::SO2::State*>(_state), angle);
mSpace->fromAngle(static_cast<statespace::SO2::State*>(_state), angle);
return true;
}

Expand Down
4 changes: 2 additions & 2 deletions src/distance/SO2Angular.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@ double SO2Angular::distance(
const aikido::statespace::StateSpace::State* _state2) const
{
// Difference between angles
double diff = mStateSpace->getAngle(
double diff = mStateSpace->toAngle(
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nit: Are we correcting the variable names in this PR or not? (_state)

Copy link
Contributor Author

@aditya-vk aditya-vk May 15, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I was doing it only in the SO2.cpp/hpp since I was mostly modifying them for this PR. I think I'll leave this for another PR and just have SO2 stuff cleaned up in code style.

static_cast<const statespace::SO2::State*>(_state1))
- mStateSpace->getAngle(
- mStateSpace->toAngle(
static_cast<const statespace::SO2::State*>(_state2));
diff = std::fmod(std::fabs(diff), 2.0 * M_PI);
if (diff > M_PI)
Expand Down
Loading