Class LinearFeedbackController

Class Documentation

class LinearFeedbackController

This class has for purpose to connect Whole Body Model Predictive Controllers from https://github.com/loco-3d/crocoddyl or https://github.com/Simple-Robotics/aligator and to the low level controller.

This part of the controller interpolates the controls using the Ricatti gains and the feed-forward terms. It runs at the robot low level frequency.

In essence it computes the following joint torques \( \tau \):

\[ \tau = K_{feedback} * (x^{des} - x^{act}) + \tau_0 \]

With \( K_{feedback} \) being the feedback gain matrix a.k.a the Ricatti gains, \( x^{des} \) and \( x^{act} \) being respectively the desired and actual state of the controller, and finally \( \tau_0 \) the feed-forward term. Note that \( x^{des} \) is the point where the control has been linearized. Hence it’s the \( x_0 \) of the optimal control problem.

Public Types

using Sensor = linear_feedback_controller_msgs::Eigen::Sensor
using Control = linear_feedback_controller_msgs::Eigen::Control

Public Functions

LinearFeedbackController()
~LinearFeedbackController()
bool load(const ControllerParameters &params)
bool set_initial_state(Eigen::VectorXd const &tau_init, Eigen::VectorXd const &jq_init)
const Eigen::VectorXd &compute_control(const TimePoint &time, const Sensor &sensor, const Control &control, const bool remove_gravity_compensation_effort)
Parameters:
  • time

  • sensor

  • control

Returns:

const Eigen::VectorXd&

RobotModelBuilder::ConstSharedPtr get_robot_model() const

Public Members

EIGEN_MAKE_ALIGNED_OPERATOR_NEW