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-" + 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<NodesVariablesPhaseBased>(ee_motion_id_);
00045
00046 pure_swing_node_ids_ = ee_motion_->GetIndicesOfNonConstantNodes();
00047
00048
00049 int constraint_count = pure_swing_node_ids_.size()*Node::n_derivatives*k2D;
00050
00051 SetRows(constraint_count);
00052 }
00053
00054 Eigen::VectorXd
00055 SwingConstraint::GetValues () const
00056 {
00057 VectorXd g(GetRows());
00058
00059 int row = 0;
00060 auto nodes = ee_motion_->GetNodes();
00061 for (int node_id : pure_swing_node_ids_) {
00062
00063 auto curr = nodes.at(node_id);
00064
00065 Vector2d prev = nodes.at(node_id-1).p().topRows<k2D>();
00066 Vector2d next = nodes.at(node_id+1).p().topRows<k2D>();
00067
00068 Vector2d distance_xy = next - prev;
00069 Vector2d xy_center = prev + 0.5*distance_xy;
00070 Vector2d des_vel_center = distance_xy/t_swing_avg_;
00071 for (auto dim : {X,Y}) {
00072 g(row++) = curr.p()(dim) - xy_center(dim);
00073 g(row++) = curr.v()(dim) - des_vel_center(dim);
00074 }
00075 }
00076
00077 return g;
00078 }
00079
00080 SwingConstraint::VecBound
00081 SwingConstraint::GetBounds () const
00082 {
00083 return VecBound(GetRows(), ifopt::BoundZero);
00084 }
00085
00086 void
00087 SwingConstraint::FillJacobianBlock (std::string var_set,
00088 Jacobian& jac) const
00089 {
00090 if (var_set == ee_motion_->GetName()) {
00091 int row = 0;
00092 for (int node_id : pure_swing_node_ids_) {
00093 for (auto dim : {X,Y}) {
00094
00095 jac.coeffRef(row, ee_motion_->GetOptIndex(NodesVariables::NodeValueInfo(node_id, kPos, dim))) = 1.0;
00096 jac.coeffRef(row, ee_motion_->GetOptIndex(NodesVariables::NodeValueInfo(node_id+1, kPos, dim))) = -0.5;
00097 jac.coeffRef(row, ee_motion_->GetOptIndex(NodesVariables::NodeValueInfo(node_id-1, kPos, dim))) = -0.5;
00098 row++;
00099
00100
00101 jac.coeffRef(row, ee_motion_->GetOptIndex(NodesVariables::NodeValueInfo(node_id, kVel, dim))) = 1.0;
00102 jac.coeffRef(row, ee_motion_->GetOptIndex(NodesVariables::NodeValueInfo(node_id+1, kPos, dim))) = -1.0/t_swing_avg_;
00103 jac.coeffRef(row, ee_motion_->GetOptIndex(NodesVariables::NodeValueInfo(node_id-1, kPos, dim))) = +1.0/t_swing_avg_;
00104 row++;
00105 }
00106 }
00107 }
00108 }
00109
00110 }