range_of_motion_constraint.cc
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
32 
33 namespace towr {
34 
36  const Parameters& params,
37  const EE& ee,
38  const SplineHolder& spline_holder)
39  :TimeDiscretizationConstraint(params.t_total_,
40  params.dt_constraint_range_of_motion_,
41  "RangeOfMotionBox-" + std::to_string(ee))
42 {
43  base_linear_ = spline_holder.base_linear_;
45  ee_motion_ = spline_holder.ee_motion_.at(ee);
46 
47  max_deviation_from_nominal_ = model->GetMaximumDeviationFromNominal();
48  nominal_ee_pos_B_ = model->GetNominalStanceInBase().at(ee);
49  ee_ = ee;
50 
51  SetRows(GetNumberOfNodes()*k3D);
52 }
53 
54 int
55 RangeOfMotionConstraint::GetRow (int node, int dim) const
56 {
57  return node*k3D + dim;
58 }
59 
60 void
62 {
63  Vector3d base_W = base_linear_->GetPoint(t).p();
64  Vector3d pos_ee_W = ee_motion_->GetPoint(t).p();
66 
67  Vector3d vector_base_to_ee_W = pos_ee_W - base_W;
68  Vector3d vector_base_to_ee_B = b_R_w*(vector_base_to_ee_W);
69 
70  g.middleRows(GetRow(k, X), k3D) = vector_base_to_ee_B;
71 }
72 
73 void
74 RangeOfMotionConstraint::UpdateBoundsAtInstance (double t, int k, VecBound& bounds) const
75 {
76  for (int dim=0; dim<k3D; ++dim) {
77  ifopt::Bounds b;
78  b += nominal_ee_pos_B_(dim);
79  b.upper_ += max_deviation_from_nominal_(dim);
80  b.lower_ -= max_deviation_from_nominal_(dim);
81  bounds.at(GetRow(k,dim)) = b;
82  }
83 }
84 
85 void
87  std::string var_set,
88  Jacobian& jac) const
89 {
91  int row_start = GetRow(k,X);
92 
93  if (var_set == id::base_lin_nodes) {
94  jac.middleRows(row_start, k3D) = -1*b_R_w*base_linear_->GetJacobianWrtNodes(t, kPos);
95  }
96 
97  if (var_set == id::base_ang_nodes) {
98  Vector3d base_W = base_linear_->GetPoint(t).p();
99  Vector3d ee_pos_W = ee_motion_->GetPoint(t).p();
100  Vector3d r_W = ee_pos_W - base_W;
101  jac.middleRows(row_start, k3D) = base_angular_.DerivOfRotVecMult(t,r_W, true);
102  }
103 
104  if (var_set == id::EEMotionNodes(ee_)) {
105  jac.middleRows(row_start, k3D) = b_R_w*ee_motion_->GetJacobianWrtNodes(t,kPos);
106  }
107 
108  if (var_set == id::EESchedule(ee_)) {
109  jac.middleRows(row_start, k3D) = b_R_w*ee_motion_->GetJacobianOfPosWrtDurations(t);
110  }
111 
112 }
113 
114 } /* namespace xpp */
115 
Constraints evaluated at discretized times along a trajectory.
NodeSpline::Ptr ee_motion_
the linear position of the endeffectors.
Eigen::VectorXd VectorXd
std::shared_ptr< KinematicModel > Ptr
static std::string EESchedule(uint ee)
Eigen::SparseMatrix< double, Eigen::RowMajor > MatrixSXd
int GetRow(int node, int dimension) const
Holds pointers to fully constructed splines, that are linked to the optimization variables.
Definition: spline_holder.h:46
Converts Euler angles and derivatives to angular quantities.
NodeSpline::Ptr base_linear_
Definition: spline_holder.h:68
RangeOfMotionConstraint(const KinematicModel::Ptr &robot_model, const Parameters &params, const EE &ee, const SplineHolder &spline_holder)
Constructs a constraint instance.
static std::string EEMotionNodes(uint ee)
NodeSpline::Ptr base_angular_
Definition: spline_holder.h:69
EulerConverter base_angular_
the orientation of the base.
static constexpr int k3D
Holds the parameters to tune the optimization problem.
Definition: parameters.h:45
MatrixSXd GetRotationMatrixBaseToWorld(double t) const
Converts the Euler angles at time t to a rotation matrix.
void UpdateConstraintAtInstance(double t, int k, VectorXd &g) const override
Sets the constraint value a specific time t, corresponding to node k.
static const std::string base_ang_nodes
NodeSpline::Ptr base_linear_
the linear position of the base.
Jacobian DerivOfRotVecMult(double t, const Vector3d &v, bool inverse) const
Returns the derivative of result of the linear equation M*v.
void UpdateBoundsAtInstance(double t, int k, VecBound &) const override
Sets upper/lower bound a specific time t, corresponding to node k.
virtual void UpdateJacobianAtInstance(double t, int k, std::string, Jacobian &) const override
Sets Jacobian rows at a specific time t, corresponding to node k.
std::vector< NodeSpline::Ptr > ee_motion_
Definition: spline_holder.h:71
static const std::string base_lin_nodes


towr_core
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 7 2018 02:15:57