Skip to content

Conversation

reidchristopher
Copy link
Contributor

Changed from the earlier pull request. Removed the file writing functionality and refactored some code.

VectorXd operator()(const VectorXd& dof_vals) const;
};

enum Axis {
Copy link
Contributor

Choose a reason for hiding this comment

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

Need to namespace the enum see here

Choose a reason for hiding this comment

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

Are we using C++11? Could use enum class instead.

};

/**
* @brief The ConfinedAxisErrCalculator is a truct whose operator() calculates error of a given
Copy link
Contributor

Choose a reason for hiding this comment

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

truct -> struct


/**
* @brief The ConfinedAxisErrCalculator is a truct whose operator() calculates error of a given
* pose with respect ot the confined rotation along the defined axis.
Copy link
Contributor

Choose a reason for hiding this comment

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

ot -> to

link_(link),
tcp_(tcp),
axis_(axis),
tol_(tol_angle * M_PI / 180.0)
Copy link
Contributor

Choose a reason for hiding this comment

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

remove M_PI/180

* @param env
* @param link
* @param axis Axis of rotation
* @param tol_angle Tolerance in radians
Copy link
Contributor

Choose a reason for hiding this comment

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

Add a note that this is a +/- range

Eigen::Affine3d tcp; /**< Tool center point */

Axis axis; /**< Axis given a conical tolerance */
double tol; /**< Cone angle in degrees */
Copy link
Contributor

Choose a reason for hiding this comment

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

Units of radians

Eigen::Affine3d tcp; /**< Tool center point */

Axis axis; /**< Axis allowed to rotate */
double tol; /**< Rotation acceptable in degrees */
Copy link
Contributor

Choose a reason for hiding this comment

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

units of radians

VectorXd err(1);

// determine the error of the rotation
switch(axis_) {
Copy link
Contributor

Choose a reason for hiding this comment

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

{ on newline

return err;
}

VectorXd ConicalAxisErrCalculator::operator()(const VectorXd& dof_vals) const {
Copy link
Contributor

Choose a reason for hiding this comment

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

{ new line

VectorXd err(1);

// determine the error of the conical axis
switch(axis_) {
Copy link
Contributor

Choose a reason for hiding this comment

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

{ new line

reidchristopher and others added 2 commits August 17, 2018 17:44
…o AlignedAxis. AlignedAxis is currently not interacting consistently with positional constraints
@mpowelson mpowelson mentioned this pull request Jan 28, 2019
24 tasks
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