Skip to content

Commit d0d11e8

Browse files
committed
Fix issue with tolerance size
1 parent 06fc509 commit d0d11e8

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
@@ -55,15 +55,18 @@ struct TrajOptCartesianWaypointConfig
5555
* This is useful if you want to have a smaller tolerance for the cost than the constraint.*/
5656
bool use_tolerance_override{ false };
5757

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

6871
private:
6972
friend class boost::serialization::access;

tesseract_motion_planners/trajopt/src/trajopt_utils.cpp

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

101-
pose_info->lower_tolerance = lower_tolerance;
102-
pose_info->upper_tolerance = upper_tolerance;
101+
if (lower_tolerance.size() == 1)
102+
{
103+
pose_info->lower_tolerance = Eigen::Vector3d::Constant(lower_tolerance(0));
104+
}
105+
else if (lower_tolerance.size() == 6)
106+
{
107+
pose_info->lower_tolerance = lower_tolerance;
108+
}
109+
110+
if (upper_tolerance.size() == 1)
111+
{
112+
pose_info->upper_tolerance = Eigen::Vector3d::Constant(upper_tolerance(0));
113+
}
114+
else if (upper_tolerance.size() == 6)
115+
{
116+
pose_info->upper_tolerance = upper_tolerance;
117+
}
103118

104119
return pose_info;
105120
}

0 commit comments

Comments
 (0)