Skip to content

Commit f9ba623

Browse files
committed
Fix issue with tolerance size
1 parent 82512cd commit f9ba623

File tree

2 files changed

+29
-11
lines changed

2 files changed

+29
-11
lines changed

tesseract_motion_planners/trajopt/include/tesseract_motion_planners/trajopt/trajopt_waypoint_config.h

Lines changed: 12 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -59,15 +59,18 @@ struct CartesianWaypointConfig
5959
* This is useful if you want to have a smaller tolerance for the cost than the constraint.*/
6060
bool use_tolerance_override{ false };
6161

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

7275
tinyxml2::XMLElement* toXML(tinyxml2::XMLDocument& doc) const;
7376
};

tesseract_motion_planners/trajopt/src/trajopt_utils.cpp

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -60,8 +60,23 @@ std::shared_ptr<trajopt::TermInfo> createCartesianWaypointTermInfo(int index,
6060
pose_info->rot_coeffs = coeffs.tail<3>();
6161
}
6262

63-
pose_info->lower_tolerance = lower_tolerance;
64-
pose_info->upper_tolerance = upper_tolerance;
63+
if (lower_tolerance.size() == 1)
64+
{
65+
pose_info->lower_tolerance = Eigen::Vector3d::Constant(lower_tolerance(0));
66+
}
67+
else if (lower_tolerance.size() == 6)
68+
{
69+
pose_info->lower_tolerance = lower_tolerance;
70+
}
71+
72+
if (upper_tolerance.size() == 1)
73+
{
74+
pose_info->upper_tolerance = Eigen::Vector3d::Constant(upper_tolerance(0));
75+
}
76+
else if (upper_tolerance.size() == 6)
77+
{
78+
pose_info->upper_tolerance = upper_tolerance;
79+
}
6580

6681
return pose_info;
6782
}

0 commit comments

Comments
 (0)