33TRAJOPT_IGNORE_WARNINGS_PUSH
44#include < Eigen/Core>
55
6+ #include < trajopt_common/utils.hpp>
67#include < tesseract_environment/environment.h>
78#include < tesseract_environment/utils.h>
89#include < tesseract_kinematics/core/joint_group.h>
@@ -15,6 +16,10 @@ TRAJOPT_IGNORE_WARNINGS_POP
1516
1617namespace trajopt
1718{
19+ const double DEFAULT_EPSILON = 1e-5 ;
20+
21+ using ErrorFunctionType = std::function<Eigen::VectorXd(const Eigen::Isometry3d&, const Eigen::Isometry3d&)>;
22+
1823/* *
1924 * @brief Used to calculate the error for CartPoseTermInfo
2025 * This is converted to a cost or constraint using TrajOptCostFromErrFunc or TrajOptConstraintFromErrFunc
@@ -38,6 +43,10 @@ struct DynamicCartPoseErrCalculator : public TrajOptVectorOfVector
3843 /* * @brief A offset transform to be applied to target_frame_ location */
3944 Eigen::Isometry3d target_frame_offset_;
4045
46+ /* * @brief Error function for calculating the error in the position given the source and target positions
47+ * this defaults to tesseract_common::calcTransformError if unset*/
48+ ErrorFunctionType error_function{ nullptr };
49+
4150 /* *
4251 * @brief This is a vector of indices to be returned Default: {0, 1, 2, 3, 4, 5}
4352 *
@@ -52,16 +61,9 @@ struct DynamicCartPoseErrCalculator : public TrajOptVectorOfVector
5261 std::string target_frame,
5362 const Eigen::Isometry3d& source_frame_offset = Eigen::Isometry3d::Identity(),
5463 const Eigen::Isometry3d& target_frame_offset = Eigen::Isometry3d::Identity(),
55- Eigen::VectorXi indices = Eigen::Matrix<int , 1 , 6 >(std::vector<int >({ 0 , 1 , 2 , 3 , 4 , 5 }).data()))
56- : manip_(std::move(manip))
57- , source_frame_(std::move(source_frame))
58- , target_frame_(std::move(target_frame))
59- , source_frame_offset_(source_frame_offset)
60- , target_frame_offset_(target_frame_offset)
61- , indices_(std::move(indices))
62- {
63- assert (indices_.size () <= 6 );
64- }
64+ Eigen::VectorXi indices = Eigen::Matrix<int , 1 , 6 >(std::vector<int >({ 0 , 1 , 2 , 3 , 4 , 5 }).data()),
65+ Eigen::VectorXd lower_tolerance = {},
66+ Eigen::VectorXd upper_tolerance = {});
6567
6668 void Plot (const tesseract_visualization::Visualization::Ptr& plotter, const Eigen::VectorXd& dof_vals) override ;
6769
@@ -96,6 +98,9 @@ struct DynamicCartPoseJacCalculator : sco::MatrixOfVector
9698 */
9799 Eigen::VectorXi indices_;
98100
101+ /* * @brief perturbation amount for calculating Jacobian */
102+ double epsilon_;
103+
99104 DynamicCartPoseJacCalculator (
100105 tesseract_kinematics::JointGroup::ConstPtr manip,
101106 std::string source_frame,
@@ -109,6 +114,7 @@ struct DynamicCartPoseJacCalculator : sco::MatrixOfVector
109114 , target_frame_(std::move(target_frame))
110115 , target_frame_offset_(target_frame_offset)
111116 , indices_(std::move(indices))
117+ , epsilon_(DEFAULT_EPSILON)
112118 {
113119 assert (indices_.size () <= 6 );
114120 }
@@ -140,6 +146,10 @@ struct CartPoseErrCalculator : public TrajOptVectorOfVector
140146 /* * @brief indicates which link is active */
141147 bool is_target_active_{ true };
142148
149+ /* * @brief Error function for calculating the error in the position given the source and target positions
150+ * this defaults to tesseract_common::calcTransformError if unset*/
151+ ErrorFunctionType error_function_{ nullptr };
152+
143153 /* *
144154 * @brief This is a vector of indices to be returned Default: {0, 1, 2, 3, 4, 5}
145155 *
@@ -154,17 +164,9 @@ struct CartPoseErrCalculator : public TrajOptVectorOfVector
154164 std::string target_frame,
155165 const Eigen::Isometry3d& source_frame_offset = Eigen::Isometry3d::Identity(),
156166 const Eigen::Isometry3d& target_frame_offset = Eigen::Isometry3d::Identity(),
157- Eigen::VectorXi indices = Eigen::Matrix<int , 1 , 6 >(std::vector<int >({ 0 , 1 , 2 , 3 , 4 , 5 }).data()))
158- : manip_(std::move(manip))
159- , source_frame_(std::move(source_frame))
160- , source_frame_offset_(source_frame_offset)
161- , target_frame_(std::move(target_frame))
162- , target_frame_offset_(target_frame_offset)
163- , indices_(std::move(indices))
164- {
165- is_target_active_ = manip_->isActiveLinkName (target_frame_);
166- assert (indices_.size () <= 6 );
167- }
167+ Eigen::VectorXi indices = Eigen::Matrix<int , 1 , 6 >(std::vector<int >({ 0 , 1 , 2 , 3 , 4 , 5 }).data()),
168+ Eigen::VectorXd lower_tolerance = {},
169+ Eigen::VectorXd upper_tolerance = {});
168170
169171 void Plot (const tesseract_visualization::Visualization::Ptr& plotter, const Eigen::VectorXd& dof_vals) override ;
170172
@@ -201,6 +203,9 @@ struct CartPoseJacCalculator : sco::MatrixOfVector
201203 */
202204 Eigen::VectorXi indices_;
203205
206+ /* * @brief perturbation amount for calculating Jacobian */
207+ double epsilon_;
208+
204209 CartPoseJacCalculator (
205210 tesseract_kinematics::JointGroup::ConstPtr manip,
206211 std::string source_frame,
@@ -214,6 +219,7 @@ struct CartPoseJacCalculator : sco::MatrixOfVector
214219 , target_frame_(std::move(target_frame))
215220 , target_frame_offset_(target_frame_offset)
216221 , indices_(std::move(indices))
222+ , epsilon_(DEFAULT_EPSILON)
217223 {
218224 is_target_active_ = manip_->isActiveLinkName (target_frame_);
219225 assert (indices_.size () <= 6 );
0 commit comments