Class that implements the dynamic description of momentum dynamics as an optimal control problem, to be used by an LQR algorithm to derive a feedback sequence.
More...
#include <DynamicsFeedback.hpp>
|
void | configure (const YAML::Node &user_parameters) |
|
double | objective (const solverlqr::StateBase &state, const solverlqr::ControlBase &control, int time_id, bool is_final_timestep) |
|
solverlqr::StateBase | dynamics (const solverlqr::StateBase &state, const solverlqr::ControlBase &control, int time_id) |
|
const PlannerSetting & | getSetting () const |
|
const DynamicsSequence & | dynamicsSequence () const |
|
Class that implements the dynamic description of momentum dynamics as an optimal control problem, to be used by an LQR algorithm to derive a feedback sequence.
momentumopt::DynamicsFeedback::DynamicsFeedback |
( |
| ) |
|
|
inline |
default class constructor and destructor
void momentumopt::DynamicsFeedback::configure |
( |
const YAML::Node & |
user_parameters | ) |
|
|
private |
function to give the user the possibility to read custom parameters
solverlqr::StateBase momentumopt::DynamicsFeedback::dynamics |
( |
const solverlqr::StateBase & |
state, |
|
|
const solverlqr::ControlBase & |
control, |
|
|
int |
time_id |
|
) |
| |
|
private |
definition of the dynamics evolution for the optimal control problem
const PlannerSetting& momentumopt::DynamicsFeedback::getSetting |
( |
| ) |
const |
|
inlineprivate |
these functions give access to the planner setting and optimized motion reference plan
double momentumopt::DynamicsFeedback::objective |
( |
const solverlqr::StateBase & |
state, |
|
|
const solverlqr::ControlBase & |
control, |
|
|
int |
time_id, |
|
|
bool |
is_final_timestep |
|
) |
| |
|
private |
definition of the objective function for the optimal control problem
void momentumopt::DynamicsFeedback::setPlannerSetting |
( |
const PlannerSetting & |
setting | ) |
|
|
inline |
stores a pointer to the planner setting and reference dynamics sequence
Eigen::MatrixXd momentumopt::DynamicsFeedback::control_cost_ |
|
private |
helper vector variables for the optimization problem
pointer to dynamic sequence to be tracked
pointer to planner setting
The documentation for this class was generated from the following files: