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/terrain_constraint.h>
00031
00032
00033 namespace towr {
00034
00035
00036 TerrainConstraint::TerrainConstraint (const HeightMap::Ptr& terrain,
00037 std::string ee_motion)
00038 :ConstraintSet(kSpecifyLater, "terrain-" + ee_motion)
00039 {
00040 ee_motion_id_ = ee_motion;
00041 terrain_ = terrain;
00042 }
00043
00044 void
00045 TerrainConstraint::InitVariableDependedQuantities (const VariablesPtr& x)
00046 {
00047 ee_motion_ = x->GetComponent<NodesVariablesPhaseBased>(ee_motion_id_);
00048
00049
00050 for (int id=1; id<ee_motion_->GetNodes().size(); ++id)
00051 node_ids_.push_back(id);
00052
00053 int constraint_count = node_ids_.size();
00054 SetRows(constraint_count);
00055 }
00056
00057 Eigen::VectorXd
00058 TerrainConstraint::GetValues () const
00059 {
00060 VectorXd g(GetRows());
00061
00062 auto nodes = ee_motion_->GetNodes();
00063 int row = 0;
00064 for (int id : node_ids_) {
00065 Vector3d p = nodes.at(id).p();
00066 g(row++) = p.z() - terrain_->GetHeight(p.x(), p.y());
00067 }
00068
00069 return g;
00070 }
00071
00072 TerrainConstraint::VecBound
00073 TerrainConstraint::GetBounds () const
00074 {
00075 VecBound bounds(GetRows());
00076 double max_distance_above_terrain = 1e20;
00077
00078 int row = 0;
00079 for (int id : node_ids_) {
00080 if (ee_motion_->IsConstantNode(id))
00081 bounds.at(row) = ifopt::BoundZero;
00082 else
00083 bounds.at(row) = ifopt::Bounds(0.0, max_distance_above_terrain);
00084 row++;
00085 }
00086
00087 return bounds;
00088 }
00089
00090 void
00091 TerrainConstraint::FillJacobianBlock (std::string var_set, Jacobian& jac) const
00092 {
00093 if (var_set == ee_motion_->GetName()) {
00094 auto nodes = ee_motion_->GetNodes();
00095 int row = 0;
00096 for (int id : node_ids_) {
00097 int idx = ee_motion_->GetOptIndex(NodesVariables::NodeValueInfo(id, kPos, Z));
00098 jac.coeffRef(row, idx) = 1.0;
00099
00100 Vector3d p = nodes.at(id).p();
00101 for (auto dim : {X,Y}) {
00102 int idx = ee_motion_->GetOptIndex(NodesVariables::NodeValueInfo(id, kPos, dim));
00103 jac.coeffRef(row, idx) = -terrain_->GetDerivativeOfHeightWrt(To2D(dim), p.x(), p.y());
00104 }
00105 row++;
00106 }
00107 }
00108 }
00109
00110 }