37 std::string ee_motion)
38 :ConstraintSet(kSpecifyLater,
"terrain-" + ee_motion)
50 for (
int id=1;
id<
ee_motion_->GetNodes().size(); ++id)
66 g(row++) = p.z() -
terrain_->GetHeight(p.x(), p.y());
76 double max_distance_above_terrain = 1e20;
83 bounds.at(row) =
ifopt::Bounds(0.0, max_distance_above_terrain);
98 jac.coeffRef(row, idx) = 1.0;
101 for (
auto dim : {
X,
Y}) {
103 jac.coeffRef(row, idx) = -
terrain_->GetDerivativeOfHeightWrt(
To2D(dim), p.x(), p.y());
VecBound GetBounds() const override
static Dim2D To2D(Dim3D dim)
static const Bounds BoundZero
Composite::Ptr VariablesPtr
VectorXd GetValues() const override
Semantic information associated with a scalar node value.
std::string ee_motion_id_
the name of the endeffector variable set.
void SetRows(int num_rows)
NodesVariablesPhaseBased::Ptr ee_motion_
the position of the endeffector.
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
HeightMap::Ptr terrain_
the height map of the current terrain.
void FillJacobianBlock(std::string var_set, Jacobian &) const override
Nodes that are associated to either swing or stance phases.
std::vector< int > node_ids_
the indices of the nodes constrained.
std::vector< Bounds > VecBound
std::shared_ptr< HeightMap > Ptr
TerrainConstraint(const HeightMap::Ptr &terrain, std::string ee_motion_id)
Constructs a terrain constraint.
void InitVariableDependedQuantities(const VariablesPtr &x) override