Constrains an endeffector to lie in a box around the nominal stance. More...
#include <range_of_motion_constraint.h>
Public Types | |
using | EE = uint |
using | Vector3d = Eigen::Vector3d |
Public Types inherited from towr::TimeDiscretizationConstraint | |
using | Bounds = ifopt::Bounds |
using | VecTimes = std::vector< double > |
Public Types inherited from ifopt::ConstraintSet | |
typedef std::shared_ptr< ConstraintSet > | Ptr |
typedef Composite::Ptr | VariablesPtr |
Public Types inherited from ifopt::Component | |
typedef Eigen::SparseMatrix< double, Eigen::RowMajor > | Jacobian |
typedef std::shared_ptr< Component > | Ptr |
typedef std::vector< Bounds > | VecBound |
typedef Eigen::VectorXd | VectorXd |
Public Member Functions | |
RangeOfMotionConstraint (const KinematicModel::Ptr &robot_model, double T, double dt, const EE &ee, const SplineHolder &spline_holder) | |
Constructs a constraint instance. More... | |
virtual | ~RangeOfMotionConstraint ()=default |
Public Member Functions inherited from towr::TimeDiscretizationConstraint | |
void | FillJacobianBlock (std::string var_set, Jacobian &) const override |
VecBound | GetBounds () const override |
Eigen::VectorXd | GetValues () const override |
TimeDiscretizationConstraint (double T, double dt, std::string constraint_name) | |
Constructs a constraint for ifopt. More... | |
TimeDiscretizationConstraint (const VecTimes &dts, std::string name) | |
construct a constraint for ifopt. More... | |
virtual | ~TimeDiscretizationConstraint ()=default |
Public Member Functions inherited from ifopt::ConstraintSet | |
ConstraintSet (int n_constraints, const std::string &name) | |
Jacobian | GetJacobian () const final |
void | LinkWithVariables (const VariablesPtr &x) |
virtual | ~ConstraintSet ()=default |
Public Member Functions inherited from ifopt::Component | |
Component (int num_rows, const std::string &name) | |
std::string | GetName () const |
int | GetRows () const |
virtual void | Print (double tolerance, int &index_start) const |
void | SetRows (int num_rows) |
virtual | ~Component ()=default |
Private Member Functions | |
int | GetRow (int node, int dimension) const |
void | UpdateBoundsAtInstance (double t, int k, VecBound &) const override |
Sets upper/lower bound a specific time t, corresponding to node k. More... | |
void | UpdateConstraintAtInstance (double t, int k, VectorXd &g) const override |
Sets the constraint value a specific time t, corresponding to node k. More... | |
void | UpdateJacobianAtInstance (double t, int k, std::string, Jacobian &) const override |
Sets Jacobian rows at a specific time t, corresponding to node k. More... | |
Private Attributes | |
EulerConverter | base_angular_ |
the orientation of the base. More... | |
NodeSpline::Ptr | base_linear_ |
the linear position of the base. More... | |
EE | ee_ |
NodeSpline::Ptr | ee_motion_ |
the linear position of the endeffectors. More... | |
Eigen::Vector3d | max_deviation_from_nominal_ |
Eigen::Vector3d | nominal_ee_pos_B_ |
Additional Inherited Members | |
Static Public Attributes inherited from ifopt::Component | |
static const int | kSpecifyLater |
Protected Member Functions inherited from towr::TimeDiscretizationConstraint | |
int | GetNumberOfNodes () const |
Protected Member Functions inherited from ifopt::ConstraintSet | |
const VariablesPtr | GetVariables () const |
Protected Attributes inherited from towr::TimeDiscretizationConstraint | |
VecTimes | dts_ |
times at which the constraint is evaluated. More... | |
Constrains an endeffector to lie in a box around the nominal stance.
These constraints are necessary to avoid configurations that are outside the kinematic reach of the robot. The constraint is defined by Cartesian estimates of the reachability of each endeffector.
This constraint calculates the position of of the contact expressed in the current CoM frame and constrains it to lie in a box around the nominal/ natural contact position for that leg.
Definition at line 55 of file range_of_motion_constraint.h.
using towr::RangeOfMotionConstraint::EE = uint |
Definition at line 57 of file range_of_motion_constraint.h.
using towr::RangeOfMotionConstraint::Vector3d = Eigen::Vector3d |
Definition at line 58 of file range_of_motion_constraint.h.
towr::RangeOfMotionConstraint::RangeOfMotionConstraint | ( | const KinematicModel::Ptr & | robot_model, |
double | T, | ||
double | dt, | ||
const EE & | ee, | ||
const SplineHolder & | spline_holder | ||
) |
Constructs a constraint instance.
robot_model | The kinematic restrictions of the robot. |
T | The total duration of the optimization. |
dt | the discretization intervall at which to enforce constraints. |
ee | The endeffector for which to constrain the range. |
spline_holder | Pointer to the current variables. |
Definition at line 35 of file range_of_motion_constraint.cc.
|
virtualdefault |
|
private |
Definition at line 53 of file range_of_motion_constraint.cc.
|
overrideprivatevirtual |
Sets upper/lower bound a specific time t, corresponding to node k.
t | The time along the trajectory to set the bounds. |
k | The index of the time t, so t=k*dt |
Implements towr::TimeDiscretizationConstraint.
Definition at line 72 of file range_of_motion_constraint.cc.
|
overrideprivatevirtual |
Sets the constraint value a specific time t, corresponding to node k.
t | The time along the trajectory to set the constraint. |
k | The index of the time t, so t=k*dt |
Implements towr::TimeDiscretizationConstraint.
Definition at line 59 of file range_of_motion_constraint.cc.
|
overrideprivatevirtual |
Sets Jacobian rows at a specific time t, corresponding to node k.
t | The time along the trajcetory to set the bounds. |
k | The index of the time t, so t=k*dt |
var_set | The name of the ifopt variables currently being queried for. |
Implements towr::TimeDiscretizationConstraint.
Definition at line 84 of file range_of_motion_constraint.cc.
|
private |
the orientation of the base.
Definition at line 76 of file range_of_motion_constraint.h.
|
private |
the linear position of the base.
Definition at line 75 of file range_of_motion_constraint.h.
|
private |
Definition at line 81 of file range_of_motion_constraint.h.
|
private |
the linear position of the endeffectors.
Definition at line 77 of file range_of_motion_constraint.h.
|
private |
Definition at line 79 of file range_of_motion_constraint.h.
|
private |
Definition at line 80 of file range_of_motion_constraint.h.