Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <towr/constraints/swing_constraint.h>
00031 #include <towr/variables/cartesian_dimensions.h>
00032
00033 namespace towr {
00034
00035 SwingConstraint::SwingConstraint (std::string ee_motion)
00036 :ConstraintSet(kSpecifyLater, "Swing-Constraint-" + ee_motion)
00037 {
00038 ee_motion_id_ = ee_motion;
00039 }
00040
00041 void
00042 towr::SwingConstraint::InitVariableDependedQuantities (const VariablesPtr& x)
00043 {
00044 ee_motion_ = x->GetComponent<PhaseNodes>(ee_motion_id_);
00045
00046 pure_swing_node_ids_ = ee_motion_->GetIndicesOfNonConstantNodes();
00047
00048
00049
00050 int constraint_count = pure_swing_node_ids_.size()*2*k2D;
00051
00052 SetRows(constraint_count);
00053 }
00054
00055 Eigen::VectorXd
00056 SwingConstraint::GetValues () const
00057 {
00058 VectorXd g(GetRows());
00059
00060 int row = 0;
00061 auto nodes = ee_motion_->GetNodes();
00062 for (int node_id : pure_swing_node_ids_) {
00063
00064
00065 auto curr = nodes.at(node_id);
00066
00067 Vector2d prev = nodes.at(node_id-1).p().topRows<k2D>();
00068 Vector2d next = nodes.at(node_id+1).p().topRows<k2D>();
00069
00070 Vector2d distance_xy = next - prev;
00071 Vector2d xy_center = prev + 0.5*distance_xy;
00072 Vector2d des_vel_center = distance_xy/t_swing_avg_;
00073 for (auto dim : {X,Y}) {
00074 g(row++) = curr.p()(dim) - xy_center(dim);
00075 g(row++) = curr.v()(dim) - des_vel_center(dim);
00076 }
00077
00078 }
00079
00080 return g;
00081 }
00082
00083 SwingConstraint::VecBound
00084 SwingConstraint::GetBounds () const
00085 {
00086 return VecBound(GetRows(), ifopt::BoundZero);
00087 }
00088
00089 void
00090 SwingConstraint::FillJacobianBlock (std::string var_set,
00091 Jacobian& jac) const
00092 {
00093 if (var_set == ee_motion_->GetName()) {
00094
00095 int row = 0;
00096 for (int node_id : pure_swing_node_ids_) {
00097
00098 for (auto dim : {X,Y}) {
00099
00100 jac.coeffRef(row, ee_motion_->Index(node_id, kPos, dim)) = 1.0;
00101 jac.coeffRef(row, ee_motion_->Index(node_id+1, kPos, dim)) = -0.5;
00102 jac.coeffRef(row, ee_motion_->Index(node_id-1, kPos, dim)) = -0.5;
00103 row++;
00104
00105
00106 jac.coeffRef(row, ee_motion_->Index(node_id, kVel, dim)) = 1.0;
00107 jac.coeffRef(row, ee_motion_->Index(node_id+1, kPos, dim)) = -1.0/t_swing_avg_;
00108 jac.coeffRef(row, ee_motion_->Index(node_id-1, kPos, dim)) = +1.0/t_swing_avg_;
00109 row++;
00110 }
00111
00112
00113 }
00114 }
00115 }
00116
00117 }