Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Format using google style #98

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
21 changes: 11 additions & 10 deletions towr/include/towr/constraints/base_motion_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#ifndef TOWR_CONSTRAINTS_BASE_MOTION_CONSTRAINT_H_
#define TOWR_CONSTRAINTS_BASE_MOTION_CONSTRAINT_H_

#include <towr/variables/spline_holder.h>
#include <towr/variables/spline.h>
#include <towr/variables/spline_holder.h>

#include "time_discretization_constraint.h"

Expand All @@ -46,26 +46,27 @@ namespace towr {
* @ingroup Constraints
*/
class BaseMotionConstraint : public TimeDiscretizationConstraint {
public:
public:
/**
* @brief Links the base variables and sets hardcoded bounds on the state.
* @param T The total time of the optimization horizon.
* @param dt The discretization interval of the constraints.
* @param spline_holder Holds pointers to the base variables.
*/
BaseMotionConstraint (double T, double dt, const SplineHolder& spline_holder);
virtual ~BaseMotionConstraint () = default;
BaseMotionConstraint(double T, double dt, const SplineHolder& spline_holder);
virtual ~BaseMotionConstraint() = default;

void UpdateConstraintAtInstance (double t, int k, VectorXd& g) const override;
void UpdateBoundsAtInstance (double t, int k, VecBound&) const override;
void UpdateJacobianAtInstance(double t, int k, std::string, Jacobian&) const override;
void UpdateConstraintAtInstance(double t, int k, VectorXd& g) const override;
void UpdateBoundsAtInstance(double t, int k, VecBound&) const override;
void UpdateJacobianAtInstance(double t, int k, std::string,
Jacobian&) const override;

private:
private:
NodeSpline::Ptr base_linear_;
NodeSpline::Ptr base_angular_;

VecBound node_bounds_; ///< same bounds for each discretized node
int GetRow (int node, int dim) const;
VecBound node_bounds_; ///< same bounds for each discretized node
int GetRow(int node, int dim) const;
};

} /* namespace towr */
Expand Down
26 changes: 13 additions & 13 deletions towr/include/towr/constraints/dynamic_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,9 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#ifndef TOWR_CONSTRAINTS_DYNAMIC_CONSTRAINT_H_
#define TOWR_CONSTRAINTS_DYNAMIC_CONSTRAINT_H_

#include <towr/variables/euler_converter.h>
#include <towr/variables/spline.h>
#include <towr/variables/spline_holder.h>
#include <towr/variables/euler_converter.h>

#include <towr/models/dynamic_model.h>

Expand Down Expand Up @@ -61,7 +61,7 @@ namespace towr {
* @ingroup Constraints
*/
class DynamicConstraint : public TimeDiscretizationConstraint {
public:
public:
using Vector6d = Eigen::Matrix<double, 6, 1>;

/**
Expand All @@ -71,18 +71,17 @@ class DynamicConstraint : public TimeDiscretizationConstraint {
* @param dt the discretization intervall at which to enforce constraints.
* @param spline_holder A pointer to the current optimization variables.
*/
DynamicConstraint (const DynamicModel::Ptr& model,
double T, double dt,
const SplineHolder& spline_holder);
virtual ~DynamicConstraint () = default;
DynamicConstraint(const DynamicModel::Ptr& model, double T, double dt,
const SplineHolder& spline_holder);
virtual ~DynamicConstraint() = default;

private:
NodeSpline::Ptr base_linear_; ///< lin. base pos/vel/acc in world frame
EulerConverter base_angular_; ///< angular base state
std::vector<NodeSpline::Ptr> ee_forces_; ///< endeffector forces in world frame.
std::vector<NodeSpline::Ptr> ee_motion_; ///< endeffector position in world frame.
private:
NodeSpline::Ptr base_linear_; ///< lin. base pos/vel/acc in world frame
EulerConverter base_angular_; ///< angular base state
std::vector<NodeSpline::Ptr> ee_forces_; ///< eef forces in world frame.
std::vector<NodeSpline::Ptr> ee_motion_; ///< eff position in world frame.

mutable DynamicModel::Ptr model_; ///< the dynamic model (e.g. Centroidal)
mutable DynamicModel::Ptr model_; ///< the dynamic model (e.g. Centroidal)

/**
* @brief The row in the overall constraint for this evaluation time.
Expand All @@ -100,7 +99,8 @@ class DynamicConstraint : public TimeDiscretizationConstraint {

void UpdateConstraintAtInstance(double t, int k, VectorXd& g) const override;
void UpdateBoundsAtInstance(double t, int k, VecBound& bounds) const override;
void UpdateJacobianAtInstance(double t, int k, std::string, Jacobian&) const override;
void UpdateJacobianAtInstance(double t, int k, std::string,
Jacobian&) const override;
};

} /* namespace towr */
Expand Down
31 changes: 15 additions & 16 deletions towr/include/towr/constraints/force_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

#include <ifopt/constraint_set.h>

#include <towr/terrain/height_map.h> // for friction cone
#include <towr/variables/nodes_variables_phase_based.h>
#include <towr/terrain/height_map.h> // for friction cone

namespace towr {

Expand All @@ -53,36 +53,35 @@ namespace towr {
* @ingroup Constraints
*/
class ForceConstraint : public ifopt::ConstraintSet {
public:
public:
using Vector3d = Eigen::Vector3d;
using EE = uint;
using EE = uint;

/**
* @brief Constructs a force contraint.
* @param terrain The gradient information of the terrain for friction cone.
* @param force_limit_in_normal_direction Maximum pushing force [N].
* @param endeffector_id Which endeffector force should be constrained.
*/
ForceConstraint (const HeightMap::Ptr& terrain,
double force_limit_in_normal_direction,
EE endeffector_id);
virtual ~ForceConstraint () = default;
ForceConstraint(const HeightMap::Ptr& terrain,
double force_limit_in_normal_direction, EE endeffector_id);
virtual ~ForceConstraint() = default;

void InitVariableDependedQuantities(const VariablesPtr& x) override;

VectorXd GetValues() const override;
VecBound GetBounds() const override;
void FillJacobianBlock (std::string var_set, Jacobian&) const override;
void FillJacobianBlock(std::string var_set, Jacobian&) const override;

private:
NodesVariablesPhaseBased::Ptr ee_force_; ///< the current xyz foot forces.
NodesVariablesPhaseBased::Ptr ee_motion_; ///< the current xyz foot positions.
private:
NodesVariablesPhaseBased::Ptr ee_force_; ///< the current xyz foot forces.
NodesVariablesPhaseBased::Ptr ee_motion_; ///< the current xyz foot pos/ns.

HeightMap::Ptr terrain_; ///< gradient information at every position (x,y).
double fn_max_; ///< force limit in normal direction.
double mu_; ///< friction coeff between robot feet and terrain.
int n_constraints_per_node_; ///< number of constraint for each node.
EE ee_; ///< The endeffector force to be constrained.
HeightMap::Ptr terrain_; ///< gradient information at every position (x,y).
double fn_max_; ///< force limit in normal direction.
double mu_; ///< friction coeff between robot feet and terrain.
int n_constraints_per_node_; ///< number of constraint for each node.
EE ee_; ///< The endeffector force to be constrained.

/**
* The are those Hermite-nodes that shape the polynomial during the
Expand Down
13 changes: 6 additions & 7 deletions towr/include/towr/constraints/linear_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ namespace towr {
* @ingroup Constraints
*/
class LinearEqualityConstraint : public ifopt::ConstraintSet {
public:
public:
using MatrixXd = Eigen::MatrixXd;

/**
Expand All @@ -50,16 +50,15 @@ class LinearEqualityConstraint : public ifopt::ConstraintSet {
* @param v The vector v defining the constanct offset.
* @param variable_set The name of the variables x.
*/
LinearEqualityConstraint (const MatrixXd& M,
const VectorXd& v,
const std::string& variable_set);
virtual ~LinearEqualityConstraint () = default;
LinearEqualityConstraint(const MatrixXd& M, const VectorXd& v,
const std::string& variable_set);
virtual ~LinearEqualityConstraint() = default;

VectorXd GetValues() const final;
VecBound GetBounds() const final;
void FillJacobianBlock (std::string var_set, Jacobian&) const final;
void FillJacobianBlock(std::string var_set, Jacobian&) const final;

private:
private:
MatrixXd M_;
VectorXd v_;
std::string variable_name_;
Expand Down
26 changes: 13 additions & 13 deletions towr/include/towr/constraints/range_of_motion_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,9 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#ifndef TOWR_CONSTRAINTS_RANGE_OF_MOTION_CONSTRAINT_H_
#define TOWR_CONSTRAINTS_RANGE_OF_MOTION_CONSTRAINT_H_

#include <towr/variables/euler_converter.h>
#include <towr/variables/spline.h>
#include <towr/variables/spline_holder.h>
#include <towr/variables/euler_converter.h>

#include <towr/models/kinematic_model.h>

Expand All @@ -53,8 +53,8 @@ namespace towr {
* @ingroup Constraints
*/
class RangeOfMotionConstraint : public TimeDiscretizationConstraint {
public:
using EE = uint;
public:
using EE = uint;
using Vector3d = Eigen::Vector3d;

/**
Expand All @@ -65,25 +65,25 @@ class RangeOfMotionConstraint : public TimeDiscretizationConstraint {
* @param ee The endeffector for which to constrain the range.
* @param spline_holder Pointer to the current variables.
*/
RangeOfMotionConstraint(const KinematicModel::Ptr& robot_model,
double T, double dt,
const EE& ee,
RangeOfMotionConstraint(const KinematicModel::Ptr& robot_model, double T,
double dt, const EE& ee,
const SplineHolder& spline_holder);
virtual ~RangeOfMotionConstraint() = default;

private:
NodeSpline::Ptr base_linear_; ///< the linear position of the base.
EulerConverter base_angular_; ///< the orientation of the base.
NodeSpline::Ptr ee_motion_; ///< the linear position of the endeffectors.
private:
NodeSpline::Ptr base_linear_; ///< the linear position of the base.
EulerConverter base_angular_; ///< the orientation of the base.
NodeSpline::Ptr ee_motion_; ///< the linear position of the endeffectors.

Eigen::Vector3d max_deviation_from_nominal_;
Eigen::Vector3d nominal_ee_pos_B_;
EE ee_;

// see TimeDiscretizationConstraint for documentation
void UpdateConstraintAtInstance (double t, int k, VectorXd& g) const override;
void UpdateBoundsAtInstance (double t, int k, VecBound&) const override;
void UpdateJacobianAtInstance(double t, int k, std::string, Jacobian&) const override;
void UpdateConstraintAtInstance(double t, int k, VectorXd& g) const override;
void UpdateBoundsAtInstance(double t, int k, VecBound&) const override;
void UpdateJacobianAtInstance(double t, int k, std::string,
Jacobian&) const override;

int GetRow(int node, int dimension) const;
};
Expand Down
16 changes: 8 additions & 8 deletions towr/include/towr/constraints/spline_acc_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,21 +46,21 @@ namespace towr {
* @ingroup Constraints
*/
class SplineAccConstraint : public ifopt::ConstraintSet {
public:
public:
SplineAccConstraint(const NodeSpline::Ptr& spline, std::string name);
virtual ~SplineAccConstraint() = default;

VectorXd GetValues() const override;
VecBound GetBounds() const override;
void FillJacobianBlock (std::string var_set, Jacobian&) const override;
void FillJacobianBlock(std::string var_set, Jacobian&) const override;

private:
NodeSpline::Ptr spline_; ///< a spline comprised of polynomials
std::string node_variables_id_; /// polynomial parameterized node values
private:
NodeSpline::Ptr spline_; ///< a spline comprised of polynomials
std::string node_variables_id_; /// polynomial parameterized node values

int n_junctions_; ///< number of junctions between polynomials in spline.
int n_dim_; ///< dimensions that this polynomial represents (e.g. x,y).
std::vector<double> T_; ///< Duration of each polynomial in spline.
int n_junctions_; ///< number of junctions between polynomials in spline.
int n_dim_; ///< dimensions that this polynomial represents (e.g. x,y).
std::vector<double> T_; ///< Duration of each polynomial in spline.
};

} /* namespace towr */
Expand Down
10 changes: 5 additions & 5 deletions towr/include/towr/constraints/swing_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,23 +47,23 @@ namespace towr {
* @ingroup Constraints
*/
class SwingConstraint : public ifopt::ConstraintSet {
public:
public:
using Vector2d = Eigen::Vector2d;

/**
* @brief Links the swing constraint with current foot variables.
* @param ee_motion_id The name of the foot variables in the optimization.
*/
SwingConstraint (std::string ee_motion_id);
virtual ~SwingConstraint () = default;
SwingConstraint(std::string ee_motion_id);
virtual ~SwingConstraint() = default;

VectorXd GetValues() const override;
VecBound GetBounds() const override;
void FillJacobianBlock (std::string var_set, Jacobian&) const override;
void FillJacobianBlock(std::string var_set, Jacobian&) const override;

void InitVariableDependedQuantities(const VariablesPtr& x) override;

private:
private:
NodesVariablesPhaseBased::Ptr ee_motion_;
double t_swing_avg_ = 0.3;
std::string ee_motion_id_;
Expand Down
21 changes: 11 additions & 10 deletions towr/include/towr/constraints/terrain_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

#include <ifopt/constraint_set.h>

#include <towr/variables/nodes_variables_phase_based.h>
#include <towr/terrain/height_map.h>
#include <towr/variables/nodes_variables_phase_based.h>

namespace towr {

Expand All @@ -49,29 +49,30 @@ namespace towr {
* @ingroup Constraints
*/
class TerrainConstraint : public ifopt::ConstraintSet {
public:
public:
using Vector3d = Eigen::Vector3d;

/**
* @brief Constructs a terrain constraint.
* @param terrain The terrain height value and slope for each position x,y.
* @param ee_motion_id The name of the endeffector variable set.
*/
TerrainConstraint (const HeightMap::Ptr& terrain, std::string ee_motion_id);
virtual ~TerrainConstraint () = default;
TerrainConstraint(const HeightMap::Ptr& terrain, std::string ee_motion_id);
virtual ~TerrainConstraint() = default;

void InitVariableDependedQuantities(const VariablesPtr& x) override;

VectorXd GetValues() const override;
VecBound GetBounds() const override;
void FillJacobianBlock (std::string var_set, Jacobian&) const override;
void FillJacobianBlock(std::string var_set, Jacobian&) const override;

private:
NodesVariablesPhaseBased::Ptr ee_motion_; ///< the position of the endeffector.
HeightMap::Ptr terrain_; ///< the height map of the current terrain.
private:
NodesVariablesPhaseBased::Ptr
ee_motion_; ///< the position of the endeffector.
HeightMap::Ptr terrain_; ///< the height map of the current terrain.

std::string ee_motion_id_; ///< the name of the endeffector variable set.
std::vector<int> node_ids_; ///< the indices of the nodes constrained.
std::string ee_motion_id_; ///< the name of the endeffector variable set.
std::vector<int> node_ids_; ///< the indices of the nodes constrained.
};

} /* namespace towr */
Expand Down
Loading