|
| 1 | +/** |
| 2 | + * @file trajopt_waypoint_config.h |
| 3 | + * @brief TrajOpt waypoint configuration settings |
| 4 | + * |
| 5 | + * @author Tyler Marr |
| 6 | + * @date November 2, 2023 |
| 7 | + * @version TODO |
| 8 | + * @bug No known bugs |
| 9 | + * |
| 10 | + * @copyright Copyright (c) 2023, Southwest Research Institute |
| 11 | + * |
| 12 | + * @par License |
| 13 | + * Software License Agreement (Apache License) |
| 14 | + * @par |
| 15 | + * Licensed under the Apache License, Version 2.0 (the "License"); |
| 16 | + * you may not use this file except in compliance with the License. |
| 17 | + * You may obtain a copy of the License at |
| 18 | + * http://www.apache.org/licenses/LICENSE-2.0 |
| 19 | + * @par |
| 20 | + * Unless required by applicable law or agreed to in writing, software |
| 21 | + * distributed under the License is distributed on an "AS IS" BASIS, |
| 22 | + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 23 | + * See the License for the specific language governing permissions and |
| 24 | + * limitations under the License. |
| 25 | + */ |
| 26 | +#ifndef TESSERACT_MOTION_PLANNERS_TRAJOPT_CONFIG_TRAJOPT_WAYPOINT_CONFIG_H |
| 27 | +#define TESSERACT_MOTION_PLANNERS_TRAJOPT_CONFIG_TRAJOPT_WAYPOINT_CONFIG_H |
| 28 | + |
| 29 | +#include <tesseract_common/macros.h> |
| 30 | +TESSERACT_COMMON_IGNORE_WARNINGS_PUSH |
| 31 | +#include <trajopt/problem_description.hpp> |
| 32 | +#include <tinyxml2.h> |
| 33 | +#include <boost/algorithm/string.hpp> |
| 34 | +TESSERACT_COMMON_IGNORE_WARNINGS_POP |
| 35 | + |
| 36 | +#include <tesseract_common/utils.h> |
| 37 | + |
| 38 | +namespace tesseract_planning |
| 39 | +{ |
| 40 | +/** |
| 41 | + * @brief Config settings for cartesian waypoints |
| 42 | + */ |
| 43 | +struct CartesianWaypointConfig |
| 44 | +{ |
| 45 | + CartesianWaypointConfig() = default; |
| 46 | + CartesianWaypointConfig(const tinyxml2::XMLElement& xml_element); |
| 47 | + |
| 48 | + /** @brief If true, a cost/constraint term will be added to the problem. Default: true*/ |
| 49 | + bool enabled = true; |
| 50 | + |
| 51 | + /** @brief If true, will override existing waypoint tolerance with described tolerance here. Default: false |
| 52 | + * This is useful if you want to have a smaller tolerance for the cost than the constraint.*/ |
| 53 | + bool use_tolerance_override = false; |
| 54 | + |
| 55 | + /** @brief Distance below waypoint that is allowed. Should be size = 6. First 3 elements are dx, dy, dz. The last 3 |
| 56 | + * elements are angle axis error allowed (Eigen::AngleAxisd.axis() * Eigen::AngleAxisd.angle()) */ |
| 57 | + Eigen::VectorXd lower_tolerance; |
| 58 | + /** @brief Distance above 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::VectorXd upper_tolerance; |
| 61 | + |
| 62 | + /** @brief coefficients corresponsing to dx, dy, dz, rx, ry, rz*/ |
| 63 | + Eigen::VectorXd coeff{ Eigen::VectorXd::Constant(1, 1, 5) }; |
| 64 | + |
| 65 | + tinyxml2::XMLElement* toXML(tinyxml2::XMLDocument& doc) const; |
| 66 | +}; |
| 67 | + |
| 68 | +/** |
| 69 | + * @brief Config settings for joint waypoints. |
| 70 | + */ |
| 71 | +struct JointWaypointConfig |
| 72 | +{ |
| 73 | + JointWaypointConfig() = default; |
| 74 | + JointWaypointConfig(const tinyxml2::XMLElement& xml_element); |
| 75 | + |
| 76 | + /** @brief If true, a cost/constraint term will be added to the problem. Default: true*/ |
| 77 | + bool enabled = true; |
| 78 | + |
| 79 | + /** @brief If true, will override existing waypoint tolerance with described tolerance here. Default: false |
| 80 | + * This is useful if you want to have a smaller tolerance for the cost than the constraint.*/ |
| 81 | + bool use_tolerance_override = false; |
| 82 | + |
| 83 | + /** @brief Distance below waypoint that is allowed. Should be size of joints in a joint state*/ |
| 84 | + Eigen::VectorXd lower_tolerance; |
| 85 | + /** @brief Distance above waypoint that is allowed. Should be size of joints in a joint state*/ |
| 86 | + Eigen::VectorXd upper_tolerance; |
| 87 | + |
| 88 | + /** @brief coefficients corresponsing to joint values*/ |
| 89 | + Eigen::VectorXd coeff{ Eigen::VectorXd::Constant(1, 1, 5) }; |
| 90 | + |
| 91 | + tinyxml2::XMLElement* toXML(tinyxml2::XMLDocument& doc) const; |
| 92 | +}; |
| 93 | +} // namespace tesseract_planning |
| 94 | + |
| 95 | +#endif // TESSERACT_MOTION_PLANNERS_TRAJOPT_CONFIG_TRAJOPT_WAYPOINT_CONFIG_H |
0 commit comments