momentumopt
momentumopt::PlannerSetting Class Reference

Public Member Functions

void initialize (const std::string &cfg_file, const std::string &planner_vars_yaml="planner_variables")
 
int & get (PlannerIntParam param)
 
bool & get (PlannerBoolParam param)
 
double & get (PlannerDoubleParam param)
 
std::string & get (PlannerStringParam param)
 
Eigen::Ref< Eigen::VectorXd > get (PlannerVectorParam param)
 
std::vector< Eigen::VectorXd > & get (PlannerCVectorParam param)
 
Eigen::Ref< Eigen::VectorXi > get (PlannerIntVectorParam param)
 
std::array< Eigen::VectorXd, Problem::n_endeffs_ > & get (PlannerArrayParam param)
 
const int & get (PlannerIntParam param) const
 
const bool & get (PlannerBoolParam param) const
 
const double & get (PlannerDoubleParam param) const
 
const std::string & get (PlannerStringParam param) const
 
const std::vector< Eigen::VectorXd > & get (PlannerCVectorParam param) const
 
const Eigen::Ref< const Eigen::VectorXd > get (PlannerVectorParam param) const
 
const Eigen::Ref< const Eigen::VectorXi > get (PlannerIntVectorParam param) const
 
const std::array< Eigen::VectorXd, Problem::n_endeffs_ > & get (PlannerArrayParam param) const
 
Heuristic & heuristic ()
 
const Heuristic & heuristic () const
 

Private Attributes

Heuristic heuristic_
 
std::string cfg_file_
 
std::string save_dynamics_file_
 
std::string save_kinematics_file_
 
std::string default_solver_setting_file_
 
int num_com_viapoints_
 
int num_joint_viapoints_
 
int num_act_eefs_
 
int num_timesteps_
 
int max_time_iterations_
 
int num_dofs_
 
int num_act_dofs_
 
int num_extended_act_dofs_
 
int max_convergence_iters_
 
int num_subsamples_
 
int kd_iterations_
 
int max_trajectory_iters_
 
bool store_data_
 
bool is_time_horizon_fixed_
 
bool is_friction_cone_linear_
 
bool use_default_solver_setting_
 
bool load_kinematics_
 
bool display_motion_
 
double gravity_
 
double time_step_
 
double robot_mass_
 
double time_horizon_
 
double friction_coeff_
 
double max_time_residual_tolerance_
 
double min_time_residual_improvement_
 
double mass_times_gravity_
 
double w_trq_arm_
 
double w_trq_leg_
 
double w_time_penalty_
 
double w_time_
 
double convergence_tolerance_
 
double min_rel_height_
 
double floor_height_
 
double kin_integration_step_
 
double kin_slacks_penalty_
 
double lambda_regularization_
 
double swing_traj_via_z_
 
double w_lin_mom_tracking_
 
double w_ang_mom_tracking_
 
double w_endeff_contact_
 
double w_endeff_tracking_
 
double p_endeff_tracking_
 
double p_com_tracking_
 
double w_joint_regularization_
 
double reg_orientation_
 
Eigen::Vector2d time_range_
 
Eigen::Vector2d torque_range_
 
Eigen::Vector3d external_force_
 
Eigen::Vector3d com_displacement_
 
Eigen::Vector3d w_com_
 
Eigen::Vector3d w_lmom_
 
Eigen::Vector3d w_lmomd_
 
Eigen::Vector3d w_lmom_final_
 
Eigen::Vector3d w_amom_
 
Eigen::Vector3d w_amomd_
 
Eigen::Vector3d w_amom_final_
 
Eigen::Vector3d w_com_via_
 
Eigen::Vector3d w_frc_arm_
 
Eigen::Vector3d w_frc_leg_
 
Eigen::Vector3d w_dfrc_arm_
 
Eigen::Vector3d w_dfrc_leg_
 
Eigen::Vector3d gravity_vector_
 
Eigen::Vector3d w_com_track_
 
Eigen::Vector3d w_lmom_track_
 
Eigen::Vector3d w_amom_track_
 
Eigen::Vector3d w_kin_base_ori_
 
Eigen::Vector3d w_kin_com_
 
Eigen::Vector3d w_kin_lmom_
 
Eigen::Vector3d w_kin_amom_
 
Eigen::Vector3d w_kin_lmomd_
 
Eigen::Vector3d w_kin_amomd_
 
Eigen::Vector3d w_kin_eff_pos_
 
Eigen::Vector3d w_kin_eff_pos_nonact_
 
Eigen::VectorXd default_joint_positions_
 
Eigen::VectorXd w_kin_default_joints_
 
Eigen::VectorXd w_kin_joint_vel_
 
Eigen::VectorXd w_kin_joint_acc_
 
Eigen::VectorXd min_joint_limits_
 
Eigen::VectorXd max_joint_limits_
 
Eigen::VectorXi active_dofs_
 
Eigen::VectorXi extended_active_dofs_
 
std::vector< Eigen::VectorXd > com_viapoints_
 
std::vector< Eigen::VectorXd > joint_viapoints_
 
std::array< Eigen::VectorXd, Problem::n_endeffs_cop_range_
 
std::array< Eigen::VectorXd, Problem::n_endeffs_eff_offset_
 
Eigen::Matrix< double, Problem::n_endeffs_, 1 > max_eef_lengths_
 

Member Data Documentation

std::string momentumopt::PlannerSetting::cfg_file_
private

helper string variables for the optimization problem

std::vector<Eigen::VectorXd> momentumopt::PlannerSetting::com_viapoints_
private

via points for center of mass motion

std::array<Eigen::VectorXd, Problem::n_endeffs_> momentumopt::PlannerSetting::cop_range_
private

region of support for end-effectors

std::array<Eigen::VectorXd, Problem::n_endeffs_> momentumopt::PlannerSetting::eff_offset_
private

offset of end-effectors from center of mass

double momentumopt::PlannerSetting::gravity_
private

helper double variables for the optimization problem

Heuristic momentumopt::PlannerSetting::heuristic_
private

Type of heuristic to use in the optimization problem

std::vector<Eigen::VectorXd> momentumopt::PlannerSetting::joint_viapoints_
private

via points for joints

Eigen::Matrix<double,Problem::n_endeffs_,1> momentumopt::PlannerSetting::max_eef_lengths_
private

maximum end-effector lengths for legs and arms

int momentumopt::PlannerSetting::num_com_viapoints_
private

helper integer variables for the optimization problem

bool momentumopt::PlannerSetting::store_data_
private

helper boolean variables for the optimization problem

Eigen::Vector2d momentumopt::PlannerSetting::time_range_
private

helper vector variables for the optimization problem


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