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

Adding an abstract BarrettHandPositionCommandExecutor class #166

Merged
merged 25 commits into from
Apr 17, 2017

Conversation

gilwoolee
Copy link
Contributor

@gilwoolee gilwoolee commented Apr 12, 2017

This PR adds BarrettHandPositionCommandExecutor and renames several classes. This is necessary/convenient to have a non-simulation counterpart ros::RosBarrettHandPositionCommandExecutor which has the same execute method signature as the existing sim-mode-executor.

  • adds an abstract class BarrettHandPositionCommandExecutor which contains execute method for four finger goal positions (3 primal, 1 spread).
  • renames existing Barrett*Executor classes to SimBarrett*Executor
  • removes collideWith param from their execute method to match the abstract class's execute signature
  • addscollideWith to the contructors for SimBarrett*Executor classes
  • addssetCollideWith methods to SimBarrett*Executor classes

One question for @mkoval : shouldn't we expose step (or spin) method for all Executors, including the higher level abstract classes? (applies to #149 as well)

@coveralls
Copy link

Coverage Status

Coverage decreased (-0.1%) to 85.055% when pulling 811a63b on SimBarrettHandCommandExecutor into 9154cc4 on master.

@coveralls
Copy link

Coverage Status

Coverage decreased (-0.1%) to 85.088% when pulling dd96c10 on SimBarrettHandCommandExecutor into 855128a on master.

@coveralls
Copy link

Coverage Status

Coverage decreased (-0.1%) to 85.088% when pulling cf8f104 on SimBarrettHandCommandExecutor into 855128a 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.

I made a few comments.

Out of curiosity: The abstraction is done only for BarrettHandPositionCommandExecutor. Will you abstract BarrettFinger*CommandExecutor as well in separate PRs?

if (mInExecution)
throw std::runtime_error("Another command in execution.");

mPromise.reset(new std::promise<void>());
mProximalGoalPositions = _positions.topRows(3);
mProximalGoalPositions = _positions.topRows(3);
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 use _positions.head<3>().

if (mInExecution)
throw std::runtime_error("Another command in execution.");

mPromise.reset(new std::promise<void>());
mProximalGoalPositions = _positions.topRows(3);
mProximalGoalPositions = _positions.topRows(3);
mSpreadGoalPosition = _positions(3);
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 use brackets for indexing vector.

Eigen::Matrix<double, 4, 1> _goalPositions,
::dart::collision::CollisionGroupPtr _collideWith);
virtual std::future<void> execute(
Eigen::Matrix<double, 4, 1> goalPositions) = 0;
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 use const Eigen::Vector4d& to avoid the unnecessary copy.

Copy link
Member

Choose a reason for hiding this comment

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

Actually, make this an Eigen::VectorXd since this is now a generic interface - potentially for hardware other than the BarrettHand. E.g. we might decide to use a similar interface for the pan-tilt unit.

Also, passing a fixed-size Eigen::Matrix by value is wrong because the argument may have incorrect alignment. This is more than a nit. 😉

Copy link
Member

Choose a reason for hiding this comment

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

👍 if this is generic for arbitrary dofs. I assumed this class is generic only for Barrett Hand, which I believe the dimension of configuration is four.

/// spreads of the fingers.
/// \param _collideWith CollisionGroup to check collision with fingers.
SimBarrettHandPositionCommandExecutor(
std::array<SimBarrettFingerPositionCommandExecutorPtr, 3> _positionCommandExecutors,
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 std::array<SimBarrettFingerPositionCommandExecutorPtr, 3>&

#include <thread>

namespace aikido{
namespace control{

//=============================================================================
BarrettFingerPositionCommandExecutor::BarrettFingerPositionCommandExecutor(
SimBarrettFingerPositionCommandExecutor::SimBarrettFingerPositionCommandExecutor(
::dart::dynamics::ChainPtr _finger, int _proximal, int _distal,
Copy link
Member

Choose a reason for hiding this comment

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

Nit: We could use std::size_t instead of int to avoid unnecessary static cast.

if (mInExecution)
return false;

mCollideWith = collideWith;
Copy link
Member

Choose a reason for hiding this comment

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

Nit: mCollideWith = std::move(collideWith);

@@ -153,7 +156,7 @@ void BarrettFingerPositionCommandExecutor::step(double _timeSincePreviousCall)
if (mDistalOnly)
return;

// Check proximal collision
// Check proximal collision
bool proximalCollision = mCollisionDetector->collide(
mProximalCollisionGroup.get(), mCollideWith.get(),
mCollisionOptions, &collisionResult);
Copy link
Member

Choose a reason for hiding this comment

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

This is not added by this PR, but we don't need to pass the collision result parameter since we only check whether there is a collision or not. By passing nullptr (or not passing), we could save time to compute the exact contact information such as point, normal, and penetration depth.

bool setCollideWith(::dart::collision::CollisionGroupPtr collideWith);

private:
constexpr static double kMimicRatio = 0.333;
constexpr static double kProximalVelocity = 0.01;
Copy link
Member

@jslee02 jslee02 Apr 13, 2017

Choose a reason for hiding this comment

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

This is not added in this PR, but renaming kProximalVelocity to kProximalSpeed would make more sense since the use of this value seems the value doesn't encode the direction of motion.

bool setCollideWith(::dart::collision::CollisionGroupPtr collideWith);

private:
constexpr static double kMimicRatio = 0.333;
constexpr static double kProximalVelocity = 0.01;
constexpr static double kDistalVelocity = kProximalVelocity*kMimicRatio;
Copy link
Member

Choose a reason for hiding this comment

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

Ditto

@@ -39,6 +41,10 @@ BarrettFingerPositionCommandExecutor::BarrettFingerPositionCommandExecutor(
if (!mCollisionDetector)
throw std::invalid_argument("CollisionDetctor is null.");

if (!mCollideWith)
throw std::invalid_argument("CollideWith is null.");
Copy link
Member

Choose a reason for hiding this comment

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

If we assume mCollideWith is always not null, then we might don't need to pass the collision detector because mCollideWith has its collision detector in it (we can use it instead). Moreover, the collision detector of mCollideWith and _collisionDetector should be the same to perform collision detection anyway so not passing additional collision detector would reduce the possibility of mistake.

FYI, the collision detection between two collision groups can be done as

bool collision = mSpreadCollisionGroup->collide(mCollideWith.get(),
    mCollisionOptions, &collisionResult);


/// Returns mimic ratio, i.e. how much the distal joint moves relative to
/// Returns mimic ratio, i.e. how much the distal joint moves relative to
/// the proximal joint. The joint movements follow
/// this ratio only when both joints are moving.
/// \return mimic ratio.
static double getMimicRatio();
Copy link
Member

Choose a reason for hiding this comment

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

Nit: We could make this constexpr in this PR or leave a note as a todo.

/// Assumes that fingers are underactuated: proximal joint is actuated
/// and distal joint moves with certain mimic ratio until collision.
/// If
/// Abstract class for position commands for a Barrett Hand.
class BarrettHandPositionCommandExecutor
Copy link
Member

Choose a reason for hiding this comment

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

Rename to PositionCommandExecutor.

Eigen::Matrix<double, 4, 1> _goalPositions,
::dart::collision::CollisionGroupPtr _collideWith);
virtual std::future<void> execute(
Eigen::Matrix<double, 4, 1> goalPositions) = 0;
Copy link
Member

Choose a reason for hiding this comment

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

Actually, make this an Eigen::VectorXd since this is now a generic interface - potentially for hardware other than the BarrettHand. E.g. we might decide to use a similar interface for the pan-tilt unit.

Also, passing a fixed-size Eigen::Matrix by value is wrong because the argument may have incorrect alignment. This is more than a nit. 😉

/// Values for executing a position and spread command.
Eigen::Vector3d mProximalGoalPositions;
double mSpreadGoalPosition;
virtual void step(double timeSincePreviousCall) = 0;
Copy link
Member

Choose a reason for hiding this comment

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

Remove the timeSincePreviousCall argument. If this is necessary inside some executors, maintain this state as a member variable.

/// joint limit is reached or collision is detected.
/// Only the proximal joint is actuated; the distal joint moves with mimic ratio.
/// When collision is detected on the distal link, the finger stops.
/// When collision is detected on the proximal link, the distal link moves
/// until it reaches joint limit or until distal collision is detected.
class BarrettFingerPositionCommandExecutor
class SimBarrettFingerPositionCommandExecutor
Copy link
Member

Choose a reason for hiding this comment

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

Simulated, not Sim! 😉

::dart::dynamics::ChainPtr _finger, int _proximal, int _distal,
::dart::collision::CollisionDetectorPtr _collisionDetector,
::dart::collision::CollisionGroupPtr _collideWith,
::dart::collision::CollisionOption _collisionOptions
= ::dart::collision::CollisionOption(false, 1));
Copy link
Member

Choose a reason for hiding this comment

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

I suggest making the _collideWith argument optional. If it's not specified, default to an empty CollisionGroup.

@jslee02 jslee02 added this to the Aikido 0.1.0 milestone Apr 13, 2017
@gilwoolee
Copy link
Contributor Author

@jslee02 As far as I know, I don't think it's necessary to create an abstract class for fingers. The abstraction at hand level is necessary so that both simulation-mode and real-mode can be handled by the same API. The real-mode does not need finger-executors; we just need to call something like RosBarrettHandPositionCommandExecutor::execute(goalPosition) that sends commands using actionlib. On a separate thread (e.g. in libherb) we'll have a MultiplexExecutor that calls step() method of RosBarrettHandPositionCommandExecutor( BarrettHandKinematicSimulationExecutor) to check the execution status (or step forward).

@gilwoolee
Copy link
Contributor Author

After discussion with @mkoval I had to make another major change: change KinematicSimulationTrajectoryExecutor::step to just step once, and remove all multi-threading component. The multi-threaded, step-forwarding part is expected to be handled by an external thread calling step() regularly. This make KinematicSimulationTrajectoryExecutor consistent with all other executors.

@mkoval @jslee02 please take a look. Thanks!

@coveralls
Copy link

Coverage Status

Coverage decreased (-0.3%) to 84.128% when pulling 06dad13 on SimBarrettHandCommandExecutor into 2b21ddd on master.

@coveralls
Copy link

Coverage Status

Coverage decreased (-0.3%) to 84.128% when pulling 06dad13 on SimBarrettHandCommandExecutor into 2b21ddd 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.

I would suggest changing collideWith as optional like @mkoval suggested. Otherwise, looks good to me.

/// the proximal joint. The joint movements follow
/// this ratio only when both joints are moving.
/// \return mimic ratio.
static double getMimicRatio();
constexpr static double getMimicRatio() { return kMimicRatio; };
Copy link
Member

Choose a reason for hiding this comment

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

Nit: Redundant trailing semicolon

/// See dart/collison/Option.h for more information
BarrettFingerKinematicSimulationPositionCommandExecutor(
::dart::dynamics::ChainPtr finger, size_t proximal, size_t distal,
::dart::collision::CollisionGroupPtr collideWith,
Copy link
Member

Choose a reason for hiding this comment

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

As @mkoval suggested, we could make collideWith optional and pass nullptr as default. Also, as becoming collideWith optional, here are necessary and optional changes I can think of:

  • We should pass collision detector, which is the same that created collideWith (if it's not nullptr).
  • If _collisionDetector is nullptr, we could create a collision detector of default collision detector type (FCL?) and assign it to mCollisionDetector.
  • If collideWith's collision detector is not the same, we could create new collision group (new collideWith) from mCollisionDetector. In this case, we might want to print warning that the mCollideWith is not the same with collideWith.

Copy link
Contributor

Choose a reason for hiding this comment

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

My understanding is that the arguments should be finger, proximal, distal (which are all required arguments), collisionDetector and collideWith (which are both optional and default to nullptr), and collisionOptions (which remains optional and defaults to false and 1).

It seems like the three cases are:

  1. If collisionDetector and collideWith are not specified, set collisionDetector to an FCLCollisionDetector and collideWith to a new empty CollisionGroup with that collision detector.
  2. If collisionDetector is specified and collideWith is not, set collideWith to a new empty CollisionGroup with collisionDetector as the collision detector
  3. If collisionDetector and collideWith are specified, check that the collision detector for collideWith matches collisionDetector. if not, set collideWith to a new empty CollisionGroup with collisionDetector as the collision detector

@jslee02 Is my understanding correct and if so, does e16880e seem reasonable? In particular, I'm unsure what it means for two collision detectors to not be the same. Do they have to be literally the same object or just the same type of collision detector? It also seems surprising to me to automatically set collideWith to an empty collision group if there were originally collision objects in there, so I think I might be misunderstanding something. 😕

Copy link
Member

@jslee02 jslee02 Apr 15, 2017

Choose a reason for hiding this comment

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

The three cases sound good and e16880e looks reasonable! I would like to add one additional case that collisionDetector is nullptr and collideWith is specified. In this case, we set mCollisionDetector to collideWith->getCollisionDetector().

In particular, I'm unsure what it means for two collision detectors to not be the same. Do they have to be literally the same object or just the same type of collision detector?

They have to be the same type, but don't necessarily need to be the same object (but it would be good to be the same object because it could share collision geometries -- this is an implementation detail). The main role of a collision detector is to enforce us to create collision groups of the same collision detection engines (e.g., fcl, bullet, ode). This is necessary because we cannot collide two collision groups created from different collision engines (unless a collision detection engine supports that feature, which I haven't heard about it).

The last bullet point case in my previous comment is that collideWith's collision detector (who created collideWith) is not the same type with collisionDetector. In this case, we cannot collide HERB hand with collideWith because of the reason described above. So we might want to either (1) create a new collision group from the shape frames in collideWith through collisionDetector or (2) create a collision group of HERB hand through the collision detector type of collideWith by collideWith->getCollisionDetector()->createCollisionGroup(...).

Sorry, probably my description was unclear. 😓

Copy link
Contributor

Choose a reason for hiding this comment

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

Got it, thank you for the clarification! I've rewritten the logic to add the fourth case. 😃

/// with this executor, it is necessary to lock the skeleton before
/// calling this method.
/// \param[in] timeSincePreviousCall Time interval to take.
void step(const std::chrono::milliseconds& timeSincePreviousCall);
Copy link
Member

@jslee02 jslee02 Apr 14, 2017

Choose a reason for hiding this comment

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

Please ignore if this is already discussed: Wouldn't there be a reasonable default interval time here?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

This call would always be called by BarrettHandKinematicSimulationPositionCommandExecutor::step() method, so I am not sure whether a default is necessary. We can set it to something I guess... :)

Copy link
Member

Choose a reason for hiding this comment

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

If that's the case, I'm fine with not setting a default value here.

const std::array<
BarrettFingerKinematicSimulationPositionCommandExecutorPtr, 3>& positionCommandExecutors,
BarrettFingerKinematicSimulationSpreadCommandExecutorPtr spreadCommandExecutor,
::dart::collision::CollisionGroupPtr collideWith);
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 nullptr as default? (see above)

Copy link
Contributor

Choose a reason for hiding this comment

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

I wound up basically copying and pasting the optional nullptr logic from BarrettFingerKinematicSimulationPositionCommandExecutor. Since the two classes are completely independent I didn't see an obvious way to avoid that... 😢

mProximalGoalPositions = _positions.topRows(3);
mSpreadGoalPosition = _positions(3);
mCollideWith = _collideWith;
mProximalGoalPositions = goalPositions.topRows(3);
Copy link
Member

Choose a reason for hiding this comment

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

Nit: topRows() is a method for matrices. We could the method for vectors as head<3>()

mSpreadGoalPosition = _positions(3);
mCollideWith = _collideWith;
mProximalGoalPositions = goalPositions.topRows(3);
mSpreadGoalPosition = goalPositions(3);
Copy link
Member

Choose a reason for hiding this comment

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

Nit: Brackets [ ] are preferable for vector indexing.

@brianhou brianhou requested a review from jslee02 April 15, 2017 03:56
{
if (mCollideWith)
// If a collision group is given and its collision detector does not match
// mCollisionDetector, set the collision group to an empty collision group.
Copy link
Member

Choose a reason for hiding this comment

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

We could add ShapeFrames of collideWith to the new collision group as

mCollideWith = mCollisionDetector->createCollisionGroup();
for (auto i = 0u; i < collideWith->getNumShapeFrames(); ++i)
  mCollideWith->addShapeFrame(collideWith->getShapeFrame(i));

so that still can check collision as expected.

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 left a bunch of nitpick comments. There are two more important (but still relatively easy) changes hidden in there:

  1. Remove the argument from step() on all of the classes.
  2. Hide the instantiation of the finger and spread executors inside the BarrettHandPositionCommandExecutor constructgor, since they are an implementation detail.

My expectation is that this PR will be ready to merge after we make those two changes. 👍

/// the proximal joint. The joint movements follow
/// this ratio only when both joints are moving.
/// \return mimic ratio.
static double getMimicRatio();
constexpr static double getMimicRatio() { return kMimicRatio; }
Copy link
Member

Choose a reason for hiding this comment

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

Nit: We could nix this function and just use kMimicRatio directly.

Copy link
Contributor

Choose a reason for hiding this comment

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

It seems that the only time that getMimicRatio is used is in tests, but kMimicRatio is private so getting rid of this function wouldn't work.

Copy link
Member

Choose a reason for hiding this comment

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

Understood. Let's leave it as it is.

constexpr static double kDistalVelocity = kProximalVelocity*kMimicRatio;
private:
constexpr static double kMimicRatio = 0.333;
constexpr static double kProximalSpeed = 1;
Copy link
Member

Choose a reason for hiding this comment

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

Why did kProximalSpeed change from 0.01 to 1? 🤔 Do we know which (if either) of these is correct for the BarrettHand?

Copy link
Contributor

Choose a reason for hiding this comment

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

This was because the hand was moving really slowly when we were visualizing it in sim. I don't know if either is correct. How would we check that?

Copy link
Member

Choose a reason for hiding this comment

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

I suspect we arbitrarily chose a value for testing, then. 😢

  1. Our controller calls the trapezoidalMove() function to move the hand:

  2. That function sets the E Puck property to the desired position, then the MODE property to MODE_TRAPEZOIDAL to execute the action.

  3. Here is a snippet of the description of the behavior of the hand in MODE_TRAPEZOIDAL (the full description goes into much more detail):

    [...] The BarrettHand will generate its own trapezoidal velocity profile to accelerate from its present position (using ACCEL) until it reaches max velocity (MV), then it will decelerate to reach the target endpoint position at zero velocity. [...]

So the correct way to get this value is to query the MV property on the four pucks in the BarrettHand, then use the transmission ratio to convert the motor velocity to a joint velocity. We should do this at some point (maybe file an issue?), but it's not urgent to get this right.

In the meantime, we can estimate a value by timing how long it takes the hand to close. This is all an approximation, anyway, since we are assuming the finger immediately accelerates to its maximum velocity.

From watching a YouTube video of HERB, I estimate around 1 s. Since the joint range is 140 degrees, this is around 2.4 rad/s. 🔬

Copy link
Member

Choose a reason for hiding this comment

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

On second thought, I am not sure why this value is hardcoded at all. We should use the velocity limits that are stored in the DART Skeleton. Those are currently set to 2 rad/s in herb_description, which is already in the correct ballpark. 👍

@brianhou Are you up for making that change? 😁

Copy link
Contributor

Choose a reason for hiding this comment

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

Hmm, it seems like making this change would require kProximalSpeed and kDistalSpeed to not be static, right? I'm not sure why they're static now and whether that's necessary though.

/// maxNumContacts = 1.)
BarrettFingerKinematicSimulationSpreadCommandExecutor(
std::array<::dart::dynamics::ChainPtr, 2> fingers, size_t spread,
::dart::collision::CollisionGroupPtr collideWith,
Copy link
Member

Choose a reason for hiding this comment

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

Nit: Make collideWith optional.

::dart::collision::CollisionDetectorPtr collisionDetector = nullptr,
::dart::collision::CollisionGroupPtr collideWith = nullptr);

/// Set relevant variables for moving fingers.
Copy link
Member

Choose a reason for hiding this comment

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

Nit: Confusing docstring.

constexpr static auto kWaitPeriod = std::chrono::milliseconds(1);

/// Executor for proximal and distal joints.
std::array<BarrettFingerKinematicSimulationPositionCommandExecutorPtr, 3> mPositionCommandExecutors;
Copy link
Member

Choose a reason for hiding this comment

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

Nit: Use kNumPositionExecutor instead of 3 for the template parameter.

::dart::collision::CollisionGroupPtr collideWith)
{
std::lock_guard<std::mutex> lockSpin(mMutex);

Copy link
Member

Choose a reason for hiding this comment

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

Nit: Check that collideWith->getCollisionDetector() is correct. Alternatively, update mCollisionDetector with that value.

mInExecution = true;

return mPromise->get_future();
}
}

//=============================================================================
void BarrettFingerSpreadCommandExecutor::step(double _timeSincePreviousCall)
void BarrettFingerKinematicSimulationSpreadCommandExecutor::step(
const std::chrono::milliseconds& timeSincePreviousCall)
Copy link
Member

Choose a reason for hiding this comment

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

Same comment as above. I suggest removing this parameter entirely, so this class complies with the PositionCommandExecutor interface.

// Current spread. Check that all spreads have same values.
double spread = mSpreadDofs[0]->getPosition();
for(int i=1; i < kNumFingers; ++i)
for(size_t i = 1; i < kNumFingers; ++i)
Copy link
Member

Choose a reason for hiding this comment

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

This looks like an off-by-one error. What am I missing? 🤔

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I don't think it's off-by-one. It uses the 0th-finger's spread value to check that the rest of the fingers (the other finger) has the same spread value. We implemented this because the spread is symmetric.

Copy link
Member

Choose a reason for hiding this comment

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

Got it, I see that now. 👍

if (mInExecution)
return false;

mCollideWith = collideWith;
Copy link
Member

Choose a reason for hiding this comment

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

Nit: std::move.

::dart::collision::CollisionGroupPtr collideWith)
{
std::lock_guard<std::mutex> lockSpin(mMutex);

Copy link
Member

Choose a reason for hiding this comment

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

Verify (or make) collideWIth->getCollisionDetector() be consistent with mCollisionDetector.

@brianhou
Copy link
Contributor

@mkoval @jslee02 I think I've addressed all your suggestions (except perhaps the one about reading kProximalSpeed from herb_description). Let me know if this looks good to merge!

Make test_BarrettFinger* compile (although actual execution seems to fail).
Make part of test_BarrettHand compile, although introducing `robot` as a
parameter seems like it will make testing this difficult.
@brianhou
Copy link
Contributor

brianhou commented Apr 16, 2017

I realized I forgot to fix the tests, but I've fixed some of them now so that at least they all compile and run.

  • test_BarrettFinger tests now compile, although the failures seem to indicate that step isn't actually updating anything. @gilwoolee based on our conversation earlier this afternoon, this might be expected behavior because there isn't a separate thread running? Is that correct?
  • test_BarrettHand compiles, although that's because I've commented out the majority of it. Now that robot is a parameter, it seems that testing this will become more difficult. I believe that aikido currently doesn't have any dependency on herb_description, so we can't load in the urdf as a skeleton (which makes it impossible to construct a BarrettHandCommandExecutor). Any thoughts on how to fix that?

gilwoolee and others added 2 commits April 16, 2017 18:31
Decrease expected proximal value in BarrettFingerKinematicSimulationPositionCommandExecutorTest.execute_proximalStopsAtCollsionDistalContinuesUntilCollision
@coveralls
Copy link

Coverage Status

Coverage decreased (-7.2%) to 77.233% when pulling 1eba53b on SimBarrettHandCommandExecutor into 2b21ddd on master.

@coveralls
Copy link

Coverage Status

Coverage decreased (-3.7%) to 77.233% when pulling fa23b68 on SimBarrettHandCommandExecutor into abe85e9 on master.

@gilwoolee
Copy link
Contributor Author

gilwoolee commented Apr 17, 2017

@brianhou To answer the questions:

  • Hmm. I don't think it has to do with mutli-threading, because the HandExecutors never assumed any multiple threads. We just took step multiple times in the tests with some set timeSincePreviousCall values. We need to convert those that take in step(timeSincePreviousCall) by measuring the time between execute(...) step() and see if the dof values after step() approximately matches the expected value (computed by ellapsedTime *speed. Some of the tests test collision-related behaviors, so they can just run for completion (until future returns). We should be able to get the same dof values as before.
  • I don't know how it exactly works, but @jslee02 knows about how to import resource or make some package dependency for test-only purposes. @jslee02 could you add to this?

@mkoval
Copy link
Member

mkoval commented Apr 17, 2017

The only real option I see is to include a BarrettHand model in the Aikido repository. We can put that in the test/resources directory, where we currently store files necessary to test CatkinResourceRetriever.

I suggest building herb_description and copying the standalone BH-280 URDF file out of the devel (or install) space. Then, edit the URDF file to: (1) replace all references to visual geometry with the collision geometry to reduce the number of binary mesh files that we need to copy and (2) modify the path to mesh files to resolve when we run unit tests.

@jslee02 had some trouble with (2) in DART, but was able to work around it using a custom ResourceRetriever. He may be able to shed some light about how to approach this.

@jslee02
Copy link
Member

jslee02 commented Apr 17, 2017

Do we want to test BarrettHandKinematicSimulationPositionCommandExecutor that is dependent on herb_description? If so, I would like to suggest moving this class (and other BarrettHand related classes) to libherb since it's not a robot agnostic implementation.

@brianhou
Copy link
Contributor

We decided that the right thing to do is to include a Barrett hand model in the repository at some point. In the meantime, we'll merge this (to unblock other PRs) and open an issue to fix that.

@brianhou brianhou merged commit 4db6fe5 into master Apr 17, 2017
@brianhou brianhou mentioned this pull request Apr 17, 2017
Shushman pushed a commit that referenced this pull request Apr 17, 2017
Merge branch 'master' into rosBarrettHandExecutor
@jslee02 jslee02 deleted the SimBarrettHandCommandExecutor branch April 27, 2017 22:57
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