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

Added SNS Acceleration IK Solver Interface with UnitTest #102

Open
wants to merge 4 commits into
base: indigo-devel
Choose a base branch
from

Conversation

robodreamer
Copy link

@robodreamer robodreamer commented Sep 27, 2018

  • added sns acceleration ik class and SNS_Base_Acc type
  • added Jacobian dot computation
  • created unit test with sawyer model
  • fixed some bugs in sns_ik_acc_base and sns_ik_vel_base codes

NOTE: Acc IK solver was created as another type of Vel IK solver,
I am trying to figure out a better way to do this, so any suggestions
are more than welcome! But this code works and it passes unit test.

- added sns acceleration ik class and SNS_Base_Acc type
- added Jacobian dot computation
- created unit test with sawyer model
Copy link

@chris-smith chris-smith left a comment

Choose a reason for hiding this comment

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

Not sure I know the code well enough to provide useful suggestions RE your note...


if (n_tasks != ntasks) {
n_tasks = ntasks;
Eigen::VectorXd ddq = Eigen::VectorXd::Zero(n_dof);

Choose a reason for hiding this comment

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

unnecessary? Or is this supposed to set a member variable?

Copy link
Author

@robodreamer robodreamer Oct 1, 2018

Choose a reason for hiding this comment

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

It is a member variable. I followed the original code (SNS velocity solvers)'s style, so it is hard to tell whether it is a local variable or not. We should revisit all these code once and revise the style..

// for the minimum bound
max = -maxJointAcceleration(i);
if (m_usePositionLimits) {
step = 2 * (jointLimit_low(i) - actualJointConfiguration(i) - actualJointVelocities(i)*loop_period) / (loop_period * loop_period);

Choose a reason for hiding this comment

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

is this taken from something specific I'm not aware of? worth a comment?

Copy link
Author

Choose a reason for hiding this comment

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

It is based on the equations in the original paper. I will add a comment.

const KDL::JntArray& q_bias,
const std::vector<std::string>& biasNames,
const KDL::JntArray& q_acc_bias,
KDL::JntArray& qddot_out)

Choose a reason for hiding this comment

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

should output variable be a pointer? That looks like the convention

Copy link
Author

@robodreamer robodreamer Oct 1, 2018

Choose a reason for hiding this comment

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

Yes. I followed the original code style, which is not necessarily good but it seemed to require a large amount of additional code changes once changed.

Copy link
Contributor

@forrest-rm forrest-rm left a comment

Choose a reason for hiding this comment

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

Overall, it looks mostly good.

// The control loop period in seconds
void setLoopPeriod(double period) { loop_period = period; }

// SNS Acceleration IK
Copy link
Contributor

Choose a reason for hiding this comment

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

This function needs more documentation for inputs and outputs

Copy link
Contributor

Choose a reason for hiding this comment

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

Overall, more documentation is still needed.


// SNS Acceleration IK
int getJointAcceleration(Eigen::VectorXd *jointAcceleration, const std::vector<TaskAcc> &sot,
const Eigen::VectorXd &jointConfiguration, const Eigen::VectorXd &jointVelocities);
Copy link
Contributor

Choose a reason for hiding this comment

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

Check alignment with previous line

int getJointAcceleration(Eigen::VectorXd *jointAcceleration, const std::vector<TaskAcc> &sot,
const Eigen::VectorXd &jointConfiguration, const Eigen::VectorXd &jointVelocities);

std::vector<double> getTasksScaleFactor()
Copy link
Contributor

Choose a reason for hiding this comment

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

The getters should be const functions:
getTaskScaleFactor() const {

Copy link
Author

Choose a reason for hiding this comment

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

Good point. Fixed it.

Eigen::ArrayXd ddotQmax; // higher joint velocity bound
std::vector<double> scaleFactors;

// variables for base acc ik solver
Copy link
Contributor

Choose a reason for hiding this comment

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

It looks like most of these variables are only used in one function. They should not be member variables.

Copy link
Author

Choose a reason for hiding this comment

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

That is right. I moved them inside the function now.

Copy link
Contributor

Choose a reason for hiding this comment

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

👍


SnsAccIkBase::uPtr baseIkSolver;

SnsIkBase::ExitCode exitCode;
Copy link
Contributor

Choose a reason for hiding this comment

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

Same here

@@ -189,9 +189,12 @@ SnsIkBase::ExitCode SnsIkBase::computeTaskScalingFactor(const Eigen::MatrixXd& J
Eigen::ArrayXd jntScaleFactorArr(nJnt_);
Copy link
Contributor

Choose a reason for hiding this comment

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

What does "Arr" stand for?

Copy link
Author

Choose a reason for hiding this comment

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

It just indicates that the variable type is an Eigen array instead of a vector. It is the convention that was used in Matt's initial sns ik code.

for (int i = 0; i < nJnt_; i++) {
if (jntIsFree[i]) {
jntScaleFactorArr(i) = SnsIkBase::findScaleFactor(lowMargin(i), uppMargin(i), a(i));
if (jntScaleFactorArr(i) == 1 && (jointOut(i) < (qLow_(i) - SnsIkBase::BOUND_TOLERANCE) || jointOut(i) > (qUpp_(i) + SnsIkBase::BOUND_TOLERANCE)))
jntScaleFactorArr(i) = 1e-3;
Copy link
Contributor

Choose a reason for hiding this comment

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

Magic number

results.solveTime += tmp.solveTime;
results.fkLinErr += tmp.fkLinErr;
results.fkAngErr += tmp.fkAngErr;
ASSERT_LE(tmp.fkLinErr, ACC_IK_TEST_FK_LIN_TOL);
Copy link
Contributor

Choose a reason for hiding this comment

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

Should these asserts also happen when iTest == 0? If so, move them out of the else statement.

// Run the test:
/*
* Note: This seems to cause a segfault in ubuntu 16.04 with Eigen 3.3.4, but it
* works fine in Ubuntu 14.04 with Eigen 3.2.0. FIXME
Copy link
Contributor

Choose a reason for hiding this comment

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

Is there a issue on github for this?

Copy link
Author

Choose a reason for hiding this comment

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

I just created an issue for this.

*************************************************************************************************/

/*
* Run the benchmark test on all five versions of the acceleration solver.
Copy link
Contributor

Choose a reason for hiding this comment

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

There's only one acc solver right now....

Copy link
Author

Choose a reason for hiding this comment

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

Yep. Right..

- removed unnecessary variables in jacobian dot computation
- removed hard-coded numbers
- enabled sns acc ik by default (only called upon request)
- other cleanups
Copy link
Contributor

@forrest-rm forrest-rm left a comment

Choose a reason for hiding this comment

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

Overall, it looks fairly good. I just had a few questions.

Eigen::ArrayXd ddotQmax; // higher joint velocity bound
std::vector<double> scaleFactors;

// variables for base acc ik solver
Copy link
Contributor

Choose a reason for hiding this comment

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

👍

// The control loop period in seconds
void setLoopPeriod(double period) { loop_period = period; }

// SNS Acceleration IK
Copy link
Contributor

Choose a reason for hiding this comment

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

Overall, more documentation is still needed.

// check whether the acceleration limits are correctly shaped
if (ddotQmin(i) > ddotQmax(i)) {
if (ddotQmin(i) > 0) {
ROS_ERROR_STREAM("Lower limit has been reversed for J"<< i <<"!\n"<< "jointLimit_Low: " << jointLimit_low(i)
Copy link
Contributor

Choose a reason for hiding this comment

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

Need additional indentation

Copy link
Contributor

Choose a reason for hiding this comment

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

Should this return an error code and/or revert to the previous values?

@@ -28,6 +28,10 @@

namespace sns_ik {

// define some constants
static const size_t CARTESIAN_DOF = 6;
static const size_t NUM_LINKS = 9; // the number of links in robot kinematic chain
Copy link
Contributor

Choose a reason for hiding this comment

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

Why is this hard-coded and will this break things if the the DOF is different?

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.

3 participants