|
| 1 | +/** |
| 2 | + * @file cartesian_position_constraint.h |
| 3 | + * @brief The cartesian position constraint |
| 4 | + * |
| 5 | + * @author Levi Armstrong |
| 6 | + * @author Matthew Powelson |
| 7 | + * @author Colin Lewis |
| 8 | + * @date December 27, 2020 |
| 9 | + * @version TODO |
| 10 | + * @bug No known bugs |
| 11 | + * |
| 12 | + * @copyright Copyright (c) 2020, Southwest Research Institute |
| 13 | + * |
| 14 | + * @par License |
| 15 | + * Software License Agreement (Apache License) |
| 16 | + * @par |
| 17 | + * Licensed under the Apache License, Version 2.0 (the "License"); |
| 18 | + * you may not use this file except in compliance with the License. |
| 19 | + * You may obtain a copy of the License at |
| 20 | + * http://www.apache.org/licenses/LICENSE-2.0 |
| 21 | + * @par |
| 22 | + * Unless required by applicable law or agreed to in writing, software |
| 23 | + * distributed under the License is distributed on an "AS IS" BASIS, |
| 24 | + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 25 | + * See the License for the specific language governing permissions and |
| 26 | + * limitations under the License. |
| 27 | + */ |
| 28 | +#ifndef TRAJOPT_IFOPT_CARTESIAN_LINE_CONSTRAINT_H |
| 29 | +#define TRAJOPT_IFOPT_CARTESIAN_LINE_CONSTRAINT_H |
| 30 | + |
| 31 | +#include <trajopt_utils/macros.h> |
| 32 | +TRAJOPT_IGNORE_WARNINGS_PUSH |
| 33 | +#include <Eigen/Eigen> |
| 34 | +#include <ifopt/constraint_set.h> |
| 35 | + |
| 36 | +#include <tesseract_kinematics/core/joint_group.h> |
| 37 | +#include <tesseract_environment/environment.h> |
| 38 | +#include <tesseract_environment/utils.h> |
| 39 | +TRAJOPT_IGNORE_WARNINGS_POP |
| 40 | + |
| 41 | +#include <trajopt_ifopt/variable_sets/joint_position_variable.h> |
| 42 | + |
| 43 | +namespace trajopt_ifopt |
| 44 | +{ |
| 45 | +/** |
| 46 | + * @brief Contains kinematic information for the cartesian position cost; include cart point .h & remove? |
| 47 | + */ |
| 48 | +struct CartLineInfo |
| 49 | +{ |
| 50 | + EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
| 51 | + |
| 52 | + using Ptr = std::shared_ptr<CartLineInfo>; |
| 53 | + using ConstPtr = std::shared_ptr<const CartLineInfo>; |
| 54 | + |
| 55 | + CartLineInfo() = default; |
| 56 | + CartLineInfo( |
| 57 | + tesseract_kinematics::JointGroup::ConstPtr manip, |
| 58 | + std::string source_frame, |
| 59 | + std::string target_frame, |
| 60 | + const Eigen::Isometry3d& target_frame_offset1, |
| 61 | + const Eigen::Isometry3d& target_frame_offset2, |
| 62 | + const Eigen::Isometry3d& source_frame_offset = Eigen::Isometry3d::Identity(), |
| 63 | + const Eigen::VectorXi& indices = Eigen::Matrix<int, 1, 6>(std::vector<int>({ 0, 1, 2, 3, 4, 5 }).data())); |
| 64 | + |
| 65 | + /** @brief The joint group */ |
| 66 | + tesseract_kinematics::JointGroup::ConstPtr manip; |
| 67 | + |
| 68 | + /** @brief Link which should reach desired pos */ |
| 69 | + std::string source_frame; |
| 70 | + |
| 71 | + /** @brief The target frame that should be reached by the source */ |
| 72 | + std::string target_frame; |
| 73 | + |
| 74 | + /** @brief Static transform applied to the source_frame location */ |
| 75 | + Eigen::Isometry3d source_frame_offset; |
| 76 | + |
| 77 | + /** @brief Static transform applied to the target_frame location defining the starting point of the line */ |
| 78 | + Eigen::Isometry3d target_frame_offset1; |
| 79 | + |
| 80 | + /** @brief Static transform applied to the target_frame location defining the ending point of the line */ |
| 81 | + Eigen::Isometry3d target_frame_offset2; |
| 82 | + |
| 83 | + /** |
| 84 | + * @brief This is a vector of indices to be returned Default: {0, 1, 2, 3, 4, 5} |
| 85 | + * |
| 86 | + * If you only care about x, y and z error, this is {0, 1, 2} |
| 87 | + * If you only care about rotation error around x, y and z, this is {3, 4, 5} |
| 88 | + */ |
| 89 | + Eigen::VectorXi indices; |
| 90 | +}; |
| 91 | + |
| 92 | +/** |
| 93 | + * @brief The CartLineConstraint class |
| 94 | + */ |
| 95 | +class CartLineConstraint : public ifopt::ConstraintSet |
| 96 | +{ |
| 97 | +public: |
| 98 | + EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
| 99 | + |
| 100 | + using Ptr = std::shared_ptr<CartLineConstraint>; |
| 101 | + using ConstPtr = std::shared_ptr<const CartLineConstraint>; |
| 102 | + |
| 103 | + CartLineConstraint(CartLineInfo info, |
| 104 | + JointPosition::ConstPtr position_var, |
| 105 | + const Eigen::VectorXd& coeffs, |
| 106 | + const std::string& name = "CartLine"); |
| 107 | + |
| 108 | + /** |
| 109 | + * @brief CalcValues Calculates the values associated with the constraint |
| 110 | + * @param joint_vals Input joint values for which FK is solved |
| 111 | + * @return Error of FK solution from target, size 6. The first 3 terms are associated with position and are currently |
| 112 | + * the only values honored for the linear model |
| 113 | + * */ |
| 114 | + Eigen::VectorXd CalcValues(const Eigen::Ref<const Eigen::VectorXd>& joint_vals) const; |
| 115 | + /** |
| 116 | + * @brief Returns the values associated with the constraint. In this case it should be the |
| 117 | + * joint values placed along the line should be n_dof_ * n_vars_ long |
| 118 | + * @return |
| 119 | + */ |
| 120 | + Eigen::VectorXd GetValues() const override; |
| 121 | + |
| 122 | + /** |
| 123 | + * @brief Returns the "bounds" of this constraint. How these are enforced is up to the solver |
| 124 | + * @return Returns the "bounds" of this constraint |
| 125 | + */ |
| 126 | + std::vector<ifopt::Bounds> GetBounds() const override; |
| 127 | + |
| 128 | + void SetBounds(const std::vector<ifopt::Bounds>& bounds); |
| 129 | + |
| 130 | + /** |
| 131 | + * @brief Fills the jacobian block associated with the constraint |
| 132 | + * @param jac_block Block of the overall jacobian associated with these constraints |
| 133 | + */ |
| 134 | + void CalcJacobianBlock(const Eigen::Ref<const Eigen::VectorXd>& joint_vals, Jacobian& jac_block) const; |
| 135 | + /** |
| 136 | + * @brief Fills the jacobian block associated with the given var_set. |
| 137 | + * @param var_set Name of the var_set to which the jac_block is associated |
| 138 | + * @param jac_block Block of the overall jacobian associated with these constraints and the var_set variable |
| 139 | + */ |
| 140 | + void FillJacobianBlock(std::string var_set, Jacobian& jac_block) const override; |
| 141 | + |
| 142 | + /** |
| 143 | + * @brief Get the two poses defining the line |
| 144 | + * @return A std::pair of poses |
| 145 | + */ |
| 146 | + std::pair<Eigen::Isometry3d, Eigen::Isometry3d> GetLine() const; |
| 147 | + |
| 148 | + /** |
| 149 | + * @brief Gets the kinematic info used to create this constraint |
| 150 | + * @return The kinematic info used to create this constraint |
| 151 | + */ |
| 152 | + const CartLineInfo& GetInfo() const; |
| 153 | + |
| 154 | + /** @brief If true, numeric differentiation will be used. Default: true |
| 155 | + * |
| 156 | + * Note: While the logic for using the jacobian from KDL will be used if set to false, this has been buggy. Set this |
| 157 | + * to false at your own risk. |
| 158 | + */ |
| 159 | + bool use_numeric_differentiation{ true }; |
| 160 | + |
| 161 | + /** |
| 162 | + * @brief GetLinePoint Finds the nearest point on the line between Isometry a,b |
| 163 | + * to a test point |
| 164 | + * @param source_tf input location, orientation to compare to the line |
| 165 | + * note that only cartesian proximity is used to determine nearness; |
| 166 | + * LinePoint orientation is determined by a SLERP between Isometry a, b |
| 167 | + * @param target_tf1 The location of the start of the line |
| 168 | + * @param target_tf2 The location of the end of the line |
| 169 | + * @return The nearest point on the line to the source_tf |
| 170 | + */ |
| 171 | + Eigen::Isometry3d GetLinePoint(const Eigen::Isometry3d& source_tf, |
| 172 | + const Eigen::Isometry3d& target_tf1, |
| 173 | + const Eigen::Isometry3d& target_tf2) const; |
| 174 | + |
| 175 | +private: |
| 176 | + /** @brief The number of joints in a single JointPosition */ |
| 177 | + long n_dof_; |
| 178 | + |
| 179 | + /** @brief The constraint coefficients */ |
| 180 | + Eigen::VectorXd coeffs_; |
| 181 | + |
| 182 | + /** @brief Bounds on the positions of each joint */ |
| 183 | + std::vector<ifopt::Bounds> bounds_; |
| 184 | + |
| 185 | + /** @brief Pointers to the vars used by this constraint. |
| 186 | + * |
| 187 | + * Do not access them directly. Instead use this->GetVariables()->GetComponent(position_var->GetName())->GetValues() |
| 188 | + */ |
| 189 | + JointPosition::ConstPtr position_var_; |
| 190 | + |
| 191 | + /** @brief The cartesian line information used when calculating error */ |
| 192 | + CartLineInfo info_; |
| 193 | +}; |
| 194 | +}; // namespace trajopt_ifopt |
| 195 | +#endif |
0 commit comments