37                                       std::string ee_motion)
    38     :ConstraintSet(kSpecifyLater, 
"Terrain-Constraint-" + ee_motion)
    50   for (
int id=1; 
id<
ee_motion_->GetNodes().size(); ++id)
    54   SetRows(constraint_count);
    66     g(row++) = p.z() - 
terrain_->GetHeight(p.x(), p.y());
    72 TerrainConstraint::VecBound
    75   VecBound bounds(GetRows());
    76   double max_distance_above_terrain = 1e20; 
    81       bounds.at(row) = ifopt::BoundZero;
    83       bounds.at(row) = ifopt::Bounds(0.0, max_distance_above_terrain);
   102       for (
auto dim : {
X,
Y})
 VecBound GetBounds() const override
Nodes that are associated to either swing or stance phases. 
static Dim2D To2D(Dim3D dim)
VectorXd GetValues() const override
std::string ee_motion_id_
the name of the endeffector variable set. 
HeightMap::Ptr terrain_
the height map of the current terrain. 
void FillJacobianBlock(std::string var_set, Jacobian &) const override
std::vector< int > node_ids_
the indices of the nodes constrained. 
PhaseNodes::Ptr ee_motion_
the position of the endeffector. 
std::shared_ptr< HeightMap > Ptr
TerrainConstraint(const HeightMap::Ptr &terrain, std::string ee_motion_id)
Constructs a terrain constraint. 
virtual void InitVariableDependedQuantities(const VariablesPtr &x) override