base_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 
34 
35 namespace towr {
36 
37 
39  const SplineHolder& spline_holder)
40  :TimeDiscretizationConstraint(params.t_total_,
41  params.dt_constraint_base_motion_,
42  "BaseMotionConstraint")
43 {
44  base_linear_ = spline_holder.base_linear_;
45  base_angular_ = spline_holder.base_angular_;
46 
47  double dev_rad = 0.1;
48  node_bounds_.resize(k6D);
49  node_bounds_.at(AX) = ifopt::NoBound;//Bounds(-dev_rad, dev_rad); euler angles bounds!
50  node_bounds_.at(AY) = ifopt::NoBound;//Bounds(-dev_rad, dev_rad);
51  node_bounds_.at(AZ) = ifopt::NoBound;//Bounds(-dev_rad, dev_rad); // NoBound
52  node_bounds_.at(LX) = ifopt::NoBound;
53  node_bounds_.at(LY) = ifopt::NoBound;//Bounds(-0.05, 0.05);
54 
55  double z_init = 0.46;//base_linear_.GetPoint(0.0).p().z();
56  node_bounds_.at(LZ) = Bounds(0.46, 0.55); // allow to move dev_z cm up and down
57 
58  int n_constraints_per_node = node_bounds_.size();
59  SetRows(GetNumberOfNodes()*n_constraints_per_node);
60 }
61 
62 void
64  VectorXd& g) const
65 {
66  g.middleRows(GetRow(k, LX), k3D) = base_linear_->GetPoint(t).p();
67  g.middleRows(GetRow(k, AX), k3D) = base_angular_->GetPoint(t).p();
68 }
69 
70 void
71 BaseMotionConstraint::UpdateBoundsAtInstance (double t, int k, VecBound& bounds) const
72 {
73  for (int dim=0; dim<node_bounds_.size(); ++dim)
74  bounds.at(GetRow(k,dim)) = node_bounds_.at(dim);
75 }
76 
77 void
79  std::string var_set,
80  Jacobian& jac) const
81 {
82  if (var_set == id::base_ang_nodes)
83  jac.middleRows(GetRow(k,AX), k3D) = base_angular_->GetJacobianWrtNodes(t, kPos);
84 
85  if (var_set == id::base_lin_nodes)
86  jac.middleRows(GetRow(k,LX), k3D) = base_linear_->GetJacobianWrtNodes(t, kPos);
87 }
88 
89 int
90 BaseMotionConstraint::GetRow (int node, int dim) const
91 {
92  return node*node_bounds_.size() + dim;
93 }
94 
95 } /* namespace towr */
VecBound node_bounds_
same bounds for each discretized node
Constraints evaluated at discretized times along a trajectory.
static constexpr int k6D
virtual void UpdateJacobianAtInstance(double t, int k, std::string, Jacobian &) const override
Sets Jacobian rows at a specific time t, corresponding to node k.
Eigen::VectorXd VectorXd
Holds pointers to fully constructed splines, that are linked to the optimization variables.
Definition: spline_holder.h:46
NodeSpline::Ptr base_linear_
Definition: spline_holder.h:68
NodeSpline::Ptr base_angular_
Definition: spline_holder.h:69
BaseMotionConstraint(const Parameters &params, const SplineHolder &spline_holder)
Links the base variables and sets hardcoded bounds on the state.
void UpdateConstraintAtInstance(double t, int k, VectorXd &g) const override
Sets the constraint value a specific time t, corresponding to node k.
static constexpr int k3D
Holds the parameters to tune the optimization problem.
Definition: parameters.h:45
static const std::string base_ang_nodes
void UpdateBoundsAtInstance(double t, int k, VecBound &) const override
Sets upper/lower bound a specific time t, corresponding to node k.
int GetRow(int node, int dim) const
static const std::string base_lin_nodes


towr_core
Author(s): Alexander W. Winkler
autogenerated on Sun Apr 8 2018 02:18:53