momentumopt
momentumopt::DynamicsFeedback Class Reference

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>

Inheritance diagram for momentumopt::DynamicsFeedback:
Collaboration diagram for momentumopt::DynamicsFeedback:

Public Member Functions

 DynamicsFeedback ()
 
void setPlannerSetting (const PlannerSetting &setting)
 
void setStatesAndControls (const DynamicsState &ini_state, const DynamicsSequence &dyn_sequence)
 

Private Member Functions

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 PlannerSettinggetSetting () const
 
const DynamicsSequencedynamicsSequence () const
 

Private Attributes

const PlannerSettingsetting_
 
const DynamicsSequenceref_dyn_sequence_
 
Eigen::MatrixXd control_cost_
 
Eigen::MatrixXd com_tracking_
 
Eigen::MatrixXd lmom_tracking_
 
Eigen::MatrixXd amom_tracking_
 
Eigen::MatrixXd com_final_tracking_
 
Eigen::MatrixXd lmom_final_tracking_
 
Eigen::MatrixXd amom_final_tracking_
 

Detailed Description

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.

Constructor & Destructor Documentation

momentumopt::DynamicsFeedback::DynamicsFeedback ( )
inline

default class constructor and destructor

Member Function Documentation

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

Member Data Documentation

Eigen::MatrixXd momentumopt::DynamicsFeedback::control_cost_
private

helper vector variables for the optimization problem

const DynamicsSequence* momentumopt::DynamicsFeedback::ref_dyn_sequence_
private

pointer to dynamic sequence to be tracked

const PlannerSetting* momentumopt::DynamicsFeedback::setting_
private

pointer to planner setting


The documentation for this class was generated from the following files: