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 issue with tolerance size #535

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 1 commit
Commits
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
Original file line number Diff line number Diff line change
Expand Up @@ -59,15 +59,18 @@ struct CartesianWaypointConfig
* This is useful if you want to have a smaller tolerance for the cost than the constraint.*/
bool use_tolerance_override{ false };

/** @brief Distance below waypoint that is allowed. Should be size = 6. First 3 elements are dx, dy, dz. The last 3
* elements are angle axis error allowed (Eigen::AngleAxisd.axis() * Eigen::AngleAxisd.angle()) */
Eigen::Matrix<double, 6, 1> lower_tolerance{ Eigen::VectorXd::Zero(6) };
/** @brief Distance above waypoint that is allowed. Should be size = 6. First 3 elements are dx, dy, dz. The last 3
* elements are angle axis error allowed (Eigen::AngleAxisd.axis() * Eigen::AngleAxisd.angle())*/
Eigen::Matrix<double, 6, 1> upper_tolerance{ Eigen::VectorXd::Zero(6) };

/** @brief coefficients corresponsing to dx, dy, dz, rx, ry, rz*/
Eigen::Matrix<double, 6, 1> coeff{ Eigen::VectorXd::Constant(6, 5) };
/** @brief Distance below waypoint that is allowed. Should be size = 6 or 1, if size = 1 the value is replicated.
* First 3 elements are dx, dy, dz. The last 3 elements are angle axis error allowed:
* (Eigen::AngleAxisd.axis() * Eigen::AngleAxisd.angle()) */
Eigen::VectorXd lower_tolerance{ Eigen::VectorXd::Zero(6) };
/** @brief Distance above waypoint that is allowed. Should be size = 6 or 1, if size = 1 the value is replicated.
* First 3 elements are dx, dy, dz. The last 3 elements are angle axis error allowed:
* (Eigen::AngleAxisd.axis() * Eigen::AngleAxisd.angle()) */
Eigen::VectorXd upper_tolerance{ Eigen::VectorXd::Zero(6) };

/** @brief coefficients corresponsing to dx, dy, dz, rx, ry, rz.
* Should be size = 6 or 1, if size = 1 the value is replicated. */
Eigen::VectorXd coeff{ Eigen::VectorXd::Constant(6, 5) };

tinyxml2::XMLElement* toXML(tinyxml2::XMLDocument& doc) const;
};
Expand Down
19 changes: 17 additions & 2 deletions tesseract_motion_planners/trajopt/src/trajopt_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,23 @@ std::shared_ptr<trajopt::TermInfo> createCartesianWaypointTermInfo(int index,
pose_info->rot_coeffs = coeffs.tail<3>();
}

pose_info->lower_tolerance = lower_tolerance;
pose_info->upper_tolerance = upper_tolerance;
if (lower_tolerance.size() == 1)
{
pose_info->lower_tolerance = Eigen::Vector3d::Constant(lower_tolerance(0));
rjoomen marked this conversation as resolved.
Show resolved Hide resolved
}
else if (lower_tolerance.size() == 6)
{
pose_info->lower_tolerance = lower_tolerance;
}

if (upper_tolerance.size() == 1)
{
pose_info->upper_tolerance = Eigen::Vector3d::Constant(upper_tolerance(0));
}
else if (upper_tolerance.size() == 6)
{
pose_info->upper_tolerance = upper_tolerance;
}

return pose_info;
}
Expand Down
Loading