|
| 1 | +/** |
| 2 | + * @file trajopt_default_composite_profile.h |
| 3 | + * @brief |
| 4 | + * |
| 5 | + * @author Levi Armstrong |
| 6 | + * @date June 18, 2020 |
| 7 | + * @version TODO |
| 8 | + * @bug No known bugs |
| 9 | + * |
| 10 | + * @copyright Copyright (c) 2020, 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 | + |
| 27 | +#ifndef TESSERACT_MOTION_PLANNERS_TRAJOPT_IFOPT_DEFAULT_COMPOSITE_PROFILE_H |
| 28 | +#define TESSERACT_MOTION_PLANNERS_TRAJOPT_IFOPT_DEFAULT_COMPOSITE_PROFILE_H |
| 29 | + |
| 30 | +#include <tesseract_common/macros.h> |
| 31 | +TESSERACT_COMMON_IGNORE_WARNINGS_PUSH |
| 32 | +#include <vector> |
| 33 | +#include <Eigen/Geometry> |
| 34 | +#include <Eigen/Core> |
| 35 | +#include <trajopt_ifopt/constraints/collision_evaluators.h> |
| 36 | +TESSERACT_COMMON_IGNORE_WARNINGS_POP |
| 37 | + |
| 38 | +#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_profile.h> |
| 39 | + |
| 40 | +namespace tesseract_planning |
| 41 | +{ |
| 42 | +class TrajOptIfoptDefaultCompositeProfile : public TrajOptIfoptCompositeProfile |
| 43 | +{ |
| 44 | +public: |
| 45 | + TrajOptIfoptDefaultCompositeProfile() = default; |
| 46 | + TrajOptIfoptDefaultCompositeProfile(const tinyxml2::XMLElement& xml_element); |
| 47 | + |
| 48 | + /** @brief Configuration info for collisions that are modeled as costs */ |
| 49 | + trajopt::TrajOptCollisionConfig::Ptr collision_cost_config; |
| 50 | + /** @brief Configuration info for collisions that are modeled as constraints */ |
| 51 | + trajopt::TrajOptCollisionConfig::Ptr collision_constraint_config; |
| 52 | + /** @brief If true, a joint velocity cost with a target of 0 will be applied for all timesteps Default: true*/ |
| 53 | + bool smooth_velocities = true; |
| 54 | + /** @brief This default to all ones, but allows you to weight different joints */ |
| 55 | + Eigen::VectorXd velocity_coeff; |
| 56 | + /** @brief If true, a joint acceleration cost with a target of 0 will be applied for all timesteps Default: false*/ |
| 57 | + bool smooth_accelerations = true; |
| 58 | + /** @brief This default to all ones, but allows you to weight different joints */ |
| 59 | + Eigen::VectorXd acceleration_coeff; |
| 60 | + /** @brief If true, a joint jerk cost with a target of 0 will be applied for all timesteps Default: false*/ |
| 61 | + bool smooth_jerks = true; |
| 62 | + /** @brief This default to all ones, but allows you to weight different joints */ |
| 63 | + Eigen::VectorXd jerk_coeff; |
| 64 | + |
| 65 | + /** @brief Set the resolution at which state validity needs to be verified in order for a motion between two states |
| 66 | + * to be considered valid in post checking of trajectory returned by TrajOptIfopt. |
| 67 | + * |
| 68 | + * The resolution is equal to longest_valid_segment_fraction * state_space.getMaximumExtent() |
| 69 | + * |
| 70 | + * Note: The planner takes the conservative of either longest_valid_segment_fraction or longest_valid_segment_length. |
| 71 | + */ |
| 72 | + double longest_valid_segment_fraction = 0.01; // 1% |
| 73 | + |
| 74 | + /** @brief Set the resolution at which state validity needs to be verified in order for a motion between two states |
| 75 | + * to be considered valid. If norm(state1 - state0) > longest_valid_segment_length. |
| 76 | + * |
| 77 | + * Note: This gets converted to longest_valid_segment_fraction. |
| 78 | + * longest_valid_segment_fraction = longest_valid_segment_length / state_space.getMaximumExtent() |
| 79 | + */ |
| 80 | + double longest_valid_segment_length = 0.5; |
| 81 | + |
| 82 | + /** @brief Special link collision cost distances */ |
| 83 | + trajopt::SafetyMarginData::Ptr special_collision_cost{ nullptr }; |
| 84 | + /** @brief Special link collision constraint distances */ |
| 85 | + trajopt::SafetyMarginData::Ptr special_collision_constraint{ nullptr }; |
| 86 | + |
| 87 | + void apply(TrajOptIfoptProblem& problem, |
| 88 | + int start_index, |
| 89 | + int end_index, |
| 90 | + const ManipulatorInfo& manip_info, |
| 91 | + const std::vector<std::string>& active_links, |
| 92 | + const std::vector<int>& fixed_indices) const override; |
| 93 | + |
| 94 | + tinyxml2::XMLElement* toXML(tinyxml2::XMLDocument& doc) const override; |
| 95 | +}; |
| 96 | +} // namespace tesseract_planning |
| 97 | + |
| 98 | +#endif // TESSERACT_MOTION_PLANNERS_TRAJOPT_IFOPT_DEFAULT_COMPOSITE_PROFILE_H |
0 commit comments