@@ -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
6871private:
6972 friend class boost ::serialization::access;
0 commit comments