@@ -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};
0 commit comments