Variables¶
Variables in the NLP are created through the following classes.
Nodes Variables¶
-
namespace
gambol -
class
NodesVariables: public VariableSet¶ - #include <NodesVariables.h>
Public Functions
-
virtual
~NodesVariables() = default¶
-
virtual NodeValueInfo
GetNodeInfo(int opt_idx) const¶ Get info of node affected by one specific optimization variable.
Reverse of
GetOptIndex().- Return
The node value affected by this optimization variable.
- Parameters
opt_idx: The index (=row) of the optimization variable.
-
virtual int
GetOptIndex(const NodeValueInfo &nvi_des) const¶ Get opt index of specific value in the stacked opt. vector
-
virtual int
GetOptIndex(int node_id, int dim) const¶ Get opt index of specific value, without the NVI struct
Get index of specific value inside the big stacked opt. vector
This function simply overload the basic and doesn’t require a NVI sturct.
-
void
SetVariables(const VectorXd &x) override¶ Sets node positions from the optimization variables.
- Parameters
x: The optimization variables.
-
int
GetDim() const¶ Return number of dimensions
-
int
GetNumNodes() const¶ Return number of nodes
-
VecBound
GetBounds() const override¶ - Return
the bounds on position and velocity of each node and dimension.
-
const Jacobian
GetNodeJacobian(int k) const¶ Returns a jacobian of a node w.r.t. the complete variable stack
Return jacobian of a node to the entire variable stack
Resulting jacobian has
dimrows anddim * n_nodescolumns. It will consist of zeros with an identity block.- Parameters
k: ID of the node to which the jacobian is for
-
void
SetByLinearInterpolation(const VectorXd &initial_val, const VectorXd &final_val)¶ Sets nodes pos/vel equally spaced from initial to final position.
- Parameters
initial_val: value of the first node.final_val: value of the final node.
-
void
SetConstantByPhase(const VectorXd &value, bool contact, const PhaseDurations::Ptr phases)¶ Sets node values for contact or flight phase.
- Parameters
value: Constant value to be setcontact: Which phase to setphases: Pointer to phases definition
-
void
AddStartBound(const std::vector<int> &dimensions, const VectorXd &val)¶ Restricts the first node in the spline.
- Parameters
dimensions: Which dimensions (x,y,z) should be restricted.val: The values the fist node should be set to.
-
void
AddFinalBound(const std::vector<int> &dimensions, const VectorXd &val)¶ Restricts the last node in the spline.
- Parameters
dimensions: Which dimensions (x,y,z) should be restricted.val: The values the last node should be set to.
-
void
AddGlobalBound(const std::vector<int> &dimensions, const std::vector<std::pair<double, double>> &limits)¶ Restricts the last node in the spline.
Set constant limits to all joints
- Parameters
dimensions: Which dimensions (x,y,z) should be restricted.limits: The min and max values
This will overwrite Start and Final bounds!
Protected Attributes
-
VecBound
bounds_¶ The bounds on the node values.
-
int
n_dim_¶ Number of values (=dimensions_ per node.
Private Functions
-
void
AddBounds(int node_id, const std::vector<int> &dim, const VectorXd &values)¶ Bounds a specific node variables.
- Parameters
node_id: The ID of the node to bound.dim: The dimension of the node to bound.values: The values to set the bounds to.
-
void
AddBound(const NodeValueInfo &node_info, double value)¶ Restricts a specific optimization variables.
- Parameters
node_info: The specs of the optimization variables to restrict.value: The value to set the bounds to.
-
struct
NodeValueInfo¶ - #include <NodesVariables.h>
Semantic information associated with a scalar node value
This includes all information except the actual value. This comes from the vector of optimization variables.
Public Functions
-
NodeValueInfo()¶
-
NodeValueInfo(int node_id, int node_dim)¶
-
int
operator==(const NodeValueInfo &right) const¶
-
-
virtual
-
class
Node Times¶
-
namespace
gambol -
class
NodeTimes¶ - #include <NodeTimes.h>
Class for the times of each node (= collocation point)
This class is not essential, but it makes it easier to share a single instance of nodes times between different components.
Public Functions
-
NodeTimes(const VecTimes ×)¶ Construct with entire list
Construct with entire list
- Parameters
times: List of all node times
-
NodeTimes(double t_total, int n_nodes)¶ Construct based on total time and number of nodes
Construct with delta_t and number of nodes
- Parameters
t_total: Total durationn_nodes: Number of nodes
-
virtual
~NodeTimes() = default¶ Destructor
-
int
GetNumberOfNodes() const¶ Return number of nodes
-
double
GetTotalTime() const¶ Get total duration
-
double
at(int k) const¶ Get single time
Get time of node k
-
int
GetNodeId(double t_des) const¶ Return id of last node before given time
Return id of node right before given time
Return first node when t < 0 and last node when t > GetTotalTime().
-
int
GetNodeId(double t_des, double &interpolation) const¶ Return id of last node and interpolation factor
Return id of node right before given time and the interpolation factor
Most right node is ignored. Method helps to interpolate random objects.
-
double
GetDeltaT(int k) const¶ Get duration of this node and the next
Get duration of this node and the next
Throws error when index is out of range
-
-
class
Phase Durations¶
-
namespace
gambol -
class
PhaseDurations¶ - #include <PhaseDurations.h>
Class for durations of phases
This class determined whether a node is part of stance or swing.
Public Functions
-
PhaseDurations(const VecDurations &initial_durations, bool is_first_phase_in_contact)¶ Constructor
- Parameters
timings: List of phase timingsis_first_phase_in_contact:trueto start in contact
-
virtual
~PhaseDurations() = default¶
-
const VecDurations &
GetPhaseDurations() const¶ Return durations
-
bool
IsContactPhase(double t) const¶ Check whether in contact at a certain time
Private Members
-
VecDurations
durations_¶ Actual durations.
-
double
t_total_¶
-
bool
initial_contact_state_¶ True if first phase in contact.
-
-
class
Nodes Holder¶
-
namespace
gambol -
struct
NodesHolder¶ - #include <NodesHolder.h>
Public Functions
-
NodesHolder() = default¶ Default constructor
-
NodesHolder(NodesVariables::Ptr joint_pos, NodesVariables::Ptr joint_vel, NodesVariables::Ptr torques, const std::vector<NodesVariables::Ptr> &ee_forces, const std::vector<PhaseDurations::Ptr> &phase_durations, NodeTimes::Ptr nodes_times)¶ Real constructor
-
virtual
~NodesHolder() = default¶ Desctructor
Public Members
-
NodesVariables::Ptr
joint_pos_¶
-
NodesVariables::Ptr
joint_vel_¶
-
NodesVariables::Ptr
torques_¶
-
std::vector<NodesVariables::Ptr>
ee_forces_¶
-
std::vector<PhaseDurations::Ptr>
phase_durations_¶
-
-
struct