Quad-SDK
Public Member Functions | Private Attributes | List of all members
NMPCController Class Reference

NMPC controller ROS node. More...

#include <nmpc_controller.h>

Collaboration diagram for NMPCController:
Collaboration graph
[legend]

Public Member Functions

 NMPCController (ros::NodeHandle &nh, int type)
 Constructor for MPCController. More...
 
bool computePlan (const Eigen::VectorXd &initial_state, const Eigen::MatrixXd &ref_traj, const std::vector< std::vector< bool > > &contact_schedule, Eigen::MatrixXd &foot_positions, Eigen::MatrixXd &foot_velocities, Eigen::MatrixXd &state_traj, Eigen::MatrixXd &control_traj)
 Update the contact and dynamic matrices, solve, and return the output. More...
 
bool computeLegPlan (const Eigen::VectorXd &initial_state, const Eigen::MatrixXd &ref_traj, const Eigen::MatrixXd &foot_positions_body, Eigen::MatrixXd &foot_positions_world, Eigen::MatrixXd &foot_velocities, const std::vector< std::vector< bool > > &contact_schedule, const Eigen::VectorXd &ref_ground_height, const double &first_element_duration, const bool &same_plan_index, const grid_map::GridMap &terrain, Eigen::MatrixXd &state_traj, Eigen::MatrixXd &control_traj)
 
Eigen::VectorXi updateAdaptiveComplexitySchedule (Eigen::MatrixXd &state_traj_lifted, Eigen::MatrixXd &control_traj_lifted)
 
void updateHorizonLength ()
 
NLPDiagnostics getNLPDiagnostics () const
 Return the NLP diagnostics. More...
 

Private Attributes

ros::NodeHandle nh_
 
int robot_id_
 
std::string robot_ns_
 Robot type: A1 or Spirit.
 
double update_rate_
 Update rate for sending and receiving data;.
 
SmartPtr< quadNLPmynlp_
 
SmartPtr< IpoptApplication > app_
 
std::shared_ptr< quad_utils::QuadKDquadKD_
 
bool enable_variable_horizon_
 
int N_
 
int N_max_
 
int N_min_
 
const int n_body_ = 12
 
const int n_foot_ = 24
 
const int n_joints_ = 24
 
const int n_tail_ = 4
 
const int m_body_ = 12
 
const int m_foot_ = 24
 
const int m_tail_ = 2
 
double dt_
 
bool require_init_
 
Eigen::VectorXi adaptive_complexity_schedule_
 Adaptive complexity schedule.
 
NLPDiagnostics diagnostics_
 Diagnostics struct for gathering metadata.
 
NLPConfig config_
 Config struct for storing meta parameters.
 

Detailed Description

NMPC controller ROS node.

Wrapper around Quadrupedal MPC that interfaces with our ROS architecture

Constructor & Destructor Documentation

◆ NMPCController()

NMPCController::NMPCController ( ros::NodeHandle &  nh,
int  type 
)

Constructor for MPCController.

Parameters
[in]nhROS NodeHandle to publish and subscribe from
Returns
Constructed object of type MPCController

Member Function Documentation

◆ computePlan()

bool NMPCController::computePlan ( const Eigen::VectorXd &  initial_state,
const Eigen::MatrixXd &  ref_traj,
const std::vector< std::vector< bool > > &  contact_schedule,
Eigen::MatrixXd &  foot_positions,
Eigen::MatrixXd &  foot_velocities,
Eigen::MatrixXd &  state_traj,
Eigen::MatrixXd &  control_traj 
)

Update the contact and dynamic matrices, solve, and return the output.

Parameters
[in]initial_stateVector with initial state
[in]ref_trajMatrix holding desired reference trajectory
[in]contact_scheduleMatrix holding the contact schedule
[in]foot_positionsMatrix holding foot positions
[in]foot_velocitiesMatrix holding foot velocities
[in]first_element_durationTime duration to the next plan index
[in]same_plan_indexIf the current solving is duplicated in the same index
[out]state_trajOptimized state trajectory output
[out]control_trajOptimized control trajectory output
Returns
good_solve

◆ getNLPDiagnostics()

NLPDiagnostics NMPCController::getNLPDiagnostics ( ) const
inline

Return the NLP diagnostics.

Returns
NLP diagnostics with most recent meta-data

◆ updateAdaptiveComplexitySchedule()

Eigen::VectorXi NMPCController::updateAdaptiveComplexitySchedule ( Eigen::MatrixXd &  state_traj_lifted,
Eigen::MatrixXd &  control_traj_lifted 
)

Method to return the constraint residual for requested data

◆ updateHorizonLength()

void NMPCController::updateHorizonLength ( )

Method to update the prediction horizon length


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