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

Add satisfiable tolerance parameter to TSR constructor #180

Merged
merged 8 commits into from
Apr 22, 2017

Conversation

dqyi11
Copy link
Contributor

@dqyi11 dqyi11 commented Apr 18, 2017

No description provided.

@dqyi11 dqyi11 requested a review from mkoval April 18, 2017 21:57
@jslee02
Copy link
Member

jslee02 commented Apr 19, 2017

I think we could simply pass the tolerance to TSR::isSatisfied(...). How do you think @mkoval ?

@dqyi11
Copy link
Contributor Author

dqyi11 commented Apr 19, 2017

@jslee02 isSatisfied() is inherited from a base class Testable.
We will still have to add similar arguments in the constructors of adapter classes unless we change isSatisfiable() of Testable.

@jslee02
Copy link
Member

jslee02 commented Apr 19, 2017

We will still have to add similar arguments in the constructors of adapter classes unless we change isSatisfiable() of Testable.

👍 I thought other Testable classes also need some tolerance but it seems not.

Copy link
Member

@jslee02 jslee02 left a comment

Choose a reason for hiding this comment

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

Could you resolve the build errors?

Also, it would be nice to have a pair of setter and getter for the tolerance.

@@ -44,7 +44,8 @@ class TSR : public Sampleable,
const Eigen::Isometry3d& _T0_w = Eigen::Isometry3d::Identity(),
const Eigen::Matrix<double, 6, 2>& _Bw =
Eigen::Matrix<double, 6, 2>::Zero(),
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity());
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity(),
const double& _satisfiableTolerance = 1e-6);
Copy link
Member

Choose a reason for hiding this comment

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

Nit: Passing const reference for primitive type is pointless. Please change to double.

@@ -57,7 +58,8 @@ class TSR : public Sampleable,
TSR(const Eigen::Isometry3d& _T0_w = Eigen::Isometry3d::Identity(),
const Eigen::Matrix<double, 6, 2>& _Bw =
Eigen::Matrix<double, 6, 2>::Zero(),
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity());
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity(),
const double& _satisfiableTolerance = 1e-6);
Copy link
Member

Choose a reason for hiding this comment

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

ditto

private:
std::unique_ptr<util::RNG> mRng;
std::shared_ptr<statespace::SE3> mStateSpace;

Copy link
Member

Choose a reason for hiding this comment

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

Nit: Could we remove this empty line?

: mT0_w(_T0_w)
, mBw(_Bw)
, mTw_e(_Tw_e)
, mRng(std::move(_rng))
, mStateSpace(std::make_shared<SE3>())
, mSatisfiableTolerance(_satisfiableTolerance)
Copy link
Member

Choose a reason for hiding this comment

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

Initialize mSatisfiableTolerance before mRng and mStateSpace to resolve the warning.

: mT0_w(_T0_w)
, mBw(_Bw)
, mTw_e(_Tw_e)
, mRng(std::unique_ptr<util::RNG>(
new util::RNGWrapper<std::default_random_engine>(0)))
, mStateSpace(std::make_shared<SE3>())
, mSatisfiableTolerance(_satisfiableTolerance)
Copy link
Member

Choose a reason for hiding this comment

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

ditto

@@ -109,6 +112,7 @@ TSR::TSR(const TSR& other)
, mTw_e(other.mTw_e)
, mRng(std::move(other.mRng->clone()))
, mStateSpace(std::make_shared<SE3>())
, mSatisfiableTolerance(other.mSatisfiableTolerance)
Copy link
Member

Choose a reason for hiding this comment

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

ditto

@@ -120,6 +124,7 @@ TSR::TSR(TSR&& other)
, mTw_e(other.mTw_e)
, mRng(std::move(other.mRng))
, mStateSpace(std::make_shared<SE3>())
, mSatisfiableTolerance(other.mSatisfiableTolerance)
Copy link
Member

Choose a reason for hiding this comment

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

ditto

@dqyi11
Copy link
Contributor Author

dqyi11 commented Apr 19, 2017

@jslee02 I addressed all your comments. Why does the order matter?
Also I put it as a public variable, because I see other member variables are public.
Shall I move it to private/protected and write get/set?

@coveralls
Copy link

Coverage Status

Coverage decreased (-0.06%) to 80.311% when pulling 03082ad on feature/add_eps_for_TSR into 2af5c55 on master.

@coveralls
Copy link

Coverage Status

Coverage decreased (-0.2%) to 80.213% when pulling a77b734 on feature/add_eps_for_TSR into 2af5c55 on master.

Copy link
Member

@jslee02 jslee02 left a comment

Choose a reason for hiding this comment

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

Looks good to me! A few minor style updates and docstring requested.

@@ -44,7 +44,8 @@ class TSR : public Sampleable,
const Eigen::Isometry3d& _T0_w = Eigen::Isometry3d::Identity(),
const Eigen::Matrix<double, 6, 2>& _Bw =
Eigen::Matrix<double, 6, 2>::Zero(),
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity());
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity(),
const double _satisfiableTolerance = 1e-6);
Copy link
Member

Choose a reason for hiding this comment

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

Nit: const is meaningless for primitive types please change this to double _satisfiableTolerance = 1e-6

Copy link
Contributor

Choose a reason for hiding this comment

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

Need docstring for the new variable.

@@ -57,7 +58,8 @@ class TSR : public Sampleable,
TSR(const Eigen::Isometry3d& _T0_w = Eigen::Isometry3d::Identity(),
const Eigen::Matrix<double, 6, 2>& _Bw =
Eigen::Matrix<double, 6, 2>::Zero(),
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity());
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity(),
const double _satisfiableTolerance = 1e-6);
Copy link
Member

Choose a reason for hiding this comment

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

ditto

@@ -112,6 +114,10 @@ class TSR : public Sampleable,
bool project(const statespace::StateSpace::State* _s,
statespace::StateSpace::State* _out) const override;

double getSatisfiableTolerance();

void setSatisfiableTolerance(const double satisfiableTolerance);
Copy link
Member

Choose a reason for hiding this comment

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

Nit: missing docstring

@@ -112,6 +114,10 @@ class TSR : public Sampleable,
bool project(const statespace::StateSpace::State* _s,
statespace::StateSpace::State* _out) const override;

double getSatisfiableTolerance();
Copy link
Member

Choose a reason for hiding this comment

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

Nit: missing docstring

@@ -79,10 +79,12 @@ class TSRSampleGenerator : public SampleGenerator

//=============================================================================
TSR::TSR(std::unique_ptr<util::RNG> _rng, const Eigen::Isometry3d& _T0_w,
const Eigen::Matrix<double, 6, 2>& _Bw, const Eigen::Isometry3d& _Tw_e)
const Eigen::Matrix<double, 6, 2>& _Bw, const Eigen::Isometry3d& _Tw_e,
const double _satisfiableTolerance)
Copy link
Member

Choose a reason for hiding this comment

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

ditto

@@ -91,10 +93,11 @@ TSR::TSR(std::unique_ptr<util::RNG> _rng, const Eigen::Isometry3d& _T0_w,

//=============================================================================
TSR::TSR(const Eigen::Isometry3d& _T0_w, const Eigen::Matrix<double, 6, 2>& _Bw,
const Eigen::Isometry3d& _Tw_e)
const Eigen::Isometry3d& _Tw_e, const double _satisfiableTolerance)
Copy link
Member

Choose a reason for hiding this comment

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

ditto

@coveralls
Copy link

Coverage Status

Coverage decreased (-0.1%) to 80.238% when pulling baa8310 on feature/add_eps_for_TSR into 2af5c55 on master.

Copy link
Contributor

@gilwoolee gilwoolee left a comment

Choose a reason for hiding this comment

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

The name mSatisfiableTolerance should be changed to mTestableTolerance, as this tolerance is being used for methods inherited from the Testable class.

While this PR is good in that it makes the arbitrary eps in the existing isSatisfied method into a member variable, I'm not sure that this is the right metric. I believe the previous use of eps was just there as a placeholder. In Vector6d representation of TSR, the first three are translation, whole the last three are for rotation. If we're to do a fix, shouldn't mTestableTolerance be a Vector6d with some default value? @mkoval @jslee02 any thoughts?

Also, I am not sure whether set and get for the tolerance is necessary. Is there a strong need to change this once a TSR is created?

@@ -44,7 +44,8 @@ class TSR : public Sampleable,
const Eigen::Isometry3d& _T0_w = Eigen::Isometry3d::Identity(),
const Eigen::Matrix<double, 6, 2>& _Bw =
Eigen::Matrix<double, 6, 2>::Zero(),
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity());
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity(),
const double _satisfiableTolerance = 1e-6);
Copy link
Contributor

Choose a reason for hiding this comment

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

Need docstring for the new variable.

@@ -112,6 +114,14 @@ class TSR : public Sampleable,
bool project(const statespace::StateSpace::State* _s,
statespace::StateSpace::State* _out) const override;

/// Get the staisfiable tolerance for isSatisfiable.
/// \param[out] _out Satisfialble tolerance, double.
double getSatisfiableTolerance();
Copy link
Contributor

Choose a reason for hiding this comment

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

Change this to getTestableTolerance(). Although, I wonder why these set and get methods are necessary. Why do we want to change the tolerance once a TSR is created?

double getSatisfiableTolerance();

/// Set the staisfiable tolerance for isSatisfiable.
/// \param _satisfiableTolerance Satisfiable tolerance to set.
Copy link
Contributor

Choose a reason for hiding this comment

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

Typo. Though not sure why we need this method.

private:
/// Tolerance for checking satisfiability
double mSatisfiableTolerance;
Copy link
Contributor

Choose a reason for hiding this comment

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

Consider changing this to Eigen::Vector6d

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Yes, I also think Eigen::Vector6d makes more sense.

@dqyi11
Copy link
Contributor Author

dqyi11 commented Apr 20, 2017

I have addressed @gilwoolee 's comments.
I have not changed it to Vector6d, because the current implementation takes the norm of the distance vector to compare with a double threshold. I will make the change if comparing two vectors is expected.
Set() and Get() are still kept. Will keep or remove after hearing back from @mkoval and @jslee02 .

@coveralls
Copy link

Coverage Status

Coverage decreased (-0.2%) to 80.213% when pulling aa443dd on feature/add_eps_for_TSR into 2af5c55 on master.

Copy link
Member

@mkoval mkoval left a comment

Choose a reason for hiding this comment

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

I am conflicted about whether the tolerance parameter should be a double or a Vector6d. On one hand, @gilwoolee raises a valid point that the elements have different units that may have dissimilar scales. On the other hand, this tolerance parameter should only be used to deal with numerical precision issues that most often occur with point TSRs: the actual tolerance is encoded in Bw.

I slightly prefer the Vector6d option, but I don't feel strongly either way. Maybe @siddhss5 can break the tie?

@@ -44,7 +44,8 @@ class TSR : public Sampleable,
const Eigen::Isometry3d& _T0_w = Eigen::Isometry3d::Identity(),
Copy link
Member

Choose a reason for hiding this comment

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

Add a docstring for _testableTolerance .

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed

@@ -44,7 +44,8 @@ class TSR : public Sampleable,
const Eigen::Isometry3d& _T0_w = Eigen::Isometry3d::Identity(),
const Eigen::Matrix<double, 6, 2>& _Bw =
Eigen::Matrix<double, 6, 2>::Zero(),
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity());
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity(),
const double _testableTolerance = 1e-6);
Copy link
Member

Choose a reason for hiding this comment

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

Don't mark arguments that are passed by value as const in function declarations.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed

@@ -57,7 +58,8 @@ class TSR : public Sampleable,
TSR(const Eigen::Isometry3d& _T0_w = Eigen::Isometry3d::Identity(),
const Eigen::Matrix<double, 6, 2>& _Bw =
Eigen::Matrix<double, 6, 2>::Zero(),
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity());
const Eigen::Isometry3d& _Tw_e = Eigen::Isometry3d::Identity(),
const double _testableTolerance = 1e-6);
Copy link
Member

Choose a reason for hiding this comment

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

Don't mark arguments that are passed by value as const in function declarations.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed

@@ -57,7 +58,8 @@ class TSR : public Sampleable,
TSR(const Eigen::Isometry3d& _T0_w = Eigen::Isometry3d::Identity(),
Copy link
Member

Choose a reason for hiding this comment

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

Add a docstring for _testableTolerance .

Copy link
Contributor Author

Choose a reason for hiding this comment

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

added.


/// Set the testable tolerance used in isSatisfiable.
/// \param _testableTolerance Testable tolerance to set.
void setTestableTolerance(const double _testableTolerance);
Copy link
Member

Choose a reason for hiding this comment

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

Don't mark arguments that are passed by value as const in function declarations.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed

@jslee02
Copy link
Member

jslee02 commented Apr 21, 2017

As a third option, we could provide either way by providing class TSR::ErrorMethod that has a virtual function that measures the error and concrete classes that implement the error measurements. Then use a reasonable one as the default.

@coveralls
Copy link

Coverage Status

Coverage decreased (-0.1%) to 80.238% when pulling ed566bf on feature/add_eps_for_TSR into 2af5c55 on master.

@jslee02 jslee02 added this to the Aikido 0.1.0 milestone Apr 22, 2017
@coveralls
Copy link

Coverage Status

Coverage decreased (-0.2%) to 79.006% when pulling 0e41653 on feature/add_eps_for_TSR into 5d19317 on master.

@gilwoolee
Copy link
Contributor

Based on what @mkoval said, double tolerance seems to be fine since it's only about numerical precision. @jslee02 's suggestion seems reasonable, but it may be an overcomplication if this is only for numerical precision.

I'm still not convinced that we need setTolerance and getTolerance. Why do we want to change tolerance after initializing it? @mkoval @jslee02 thoughts?

@coveralls
Copy link

Coverage Status

Coverage decreased (-0.1%) to 79.044% when pulling d118d2d on feature/add_eps_for_TSR into 78d38af on master.

@gilwoolee gilwoolee merged commit 4af95ae into master Apr 22, 2017
@jslee02
Copy link
Member

jslee02 commented Apr 22, 2017

Why do we want to change tolerance after initializing it? @mkoval @jslee02 thoughts?

I don't have a compelling reason to have the getters/setters but also not to have. One use case I can think of now is doing planning changing the error tolerance when it's failed to see if the failure is because of it. I'm fine either leaving them or not.

@gilwoolee gilwoolee deleted the feature/add_eps_for_TSR branch April 22, 2017 22:25
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants