Tetrapod Project
|
A class for hierarchical optimization control. More...
#include <hierarchical_optimization_controller.h>
Classes | |
struct | Task |
Task struct. More... | |
Public Types | |
enum | SolverType { OSQP = 1 , ECQP = 2 , CLP = 3 , SCS = 4 , SNOPT = 5 , UNSPECIFIED } |
Drake Solver type enumerator. More... | |
enum | LegType { frontLeft = 1 , frontRight = 2 , rearLeft = 3 , rearRight = 4 , NONE } |
Leg type enumerator. More... | |
enum | BodyType { base = 1 , hip = 2 , thigh = 3 , leg = 4 , foot = 5 } |
Body type enumerator. More... | |
Public Member Functions | |
HierarchicalOptimizationControl () | |
Constructor. More... | |
virtual | ~HierarchicalOptimizationControl () |
Destructor. More... | |
void | StaticTorqueTest () |
void | HeightRollYawTest () |
Eigen::Matrix< double, 12, 1 > | HierarchicalOptimization (const Eigen::Matrix< double, 3, 1 > &_desired_base_pos, const Eigen::Matrix< double, 3, 1 > &_desired_base_vel, const Eigen::Matrix< double, 3, 1 > &_desired_base_acc, const Eigen::Matrix< double, 3, 1 > &_desired_base_ori, const Eigen::Matrix< Eigen::Vector3d, 4, 1 > &_desired_f_pos, const Eigen::Matrix< Eigen::Vector3d, 4, 1 > &_desired_f_vel, const Eigen::Matrix< Eigen::Vector3d, 4, 1 > &_desired_f_acc, const Eigen::Matrix< Eigen::Vector3d, 4, 1 > &_f_pos, const Eigen::Matrix< Eigen::Vector3d, 4, 1 > &_f_vel, const Eigen::Matrix< double, 18, 1 > &_q, const Eigen::Matrix< double, 18, 1 > &_u, const int &_v=0) |
The HierarchicalOptimization function finds the optimal joint torques for a desired motion plan. It finds joint torques by finding optimal joint accelerations and contact forces for a set of whole-body control QP tasks, and leveraging inverse dynamics. More... | |
Eigen::Matrix< double, Eigen::Dynamic, 1 > | HierarchicalQPOptimization (const int &_state_dim, const std::vector< Task > &_tasks, const SolverType &_solver=SolverType::OSQP, const int &_v=0) |
The HierarchicalQPOptimization function finds the optimal solution for a set of tasks in a strictly prioritized order. The method iterates through the set of tasks and searches for a new solution in the null-space of all higher priority equality constraints. At each iteration a QP problem is solved to find a vector lying in the row-space of the null-space of all equality constraints, which improve on the current solution. More... | |
Eigen::Matrix< double, Eigen::Dynamic, 1 > | HierarchicalLeastSquareOptimization (const Eigen::Matrix< Eigen::MatrixXd, Eigen::Dynamic, 1 > &_A, const Eigen::Matrix< Eigen::Matrix< double, Eigen::Dynamic, 1 >, Eigen::Dynamic, 1 > &_b, const int &_v=0) |
The HierarchicalLeastSquareOptimization function finds the optimal solution for a set of linear equality constraints in a strictly prioritized order. The method iterates through the set of equality constraints and searches for a new solution in the null-space of all higher priority equality constraints. At each iteration the Moore-Penrose pseudoinverse is utilized to find a vector lying in the row-space of the null-space of all equality constraints, which improve on the current solution. The usage of the Moore-Penrose pseudoinverse yield a least square solution of the problem at hand. More... | |
bool | SolveQP (const Eigen::MatrixXd &_Q, const Eigen::VectorXd &_c, const Eigen::MatrixXd &_E_ineq, const Eigen::VectorXd &_f_ineq, Eigen::VectorXd &_sol, const SolverType &_solver=SolverType::UNSPECIFIED, const int &_v=0) |
The SolveQP function solves a (convex) quadratic program (QP) on the form: More... | |
bool | SolveQP (const Eigen::MatrixXd &_Q, const Eigen::VectorXd &_c, const Eigen::MatrixXd &_A, const Eigen::VectorXd &_lb, const Eigen::VectorXd &_ub, Eigen::VectorXd &_sol, const SolverType &_solver=SolverType::UNSPECIFIED, const int &_v=0) |
The SolveQP function solves a (convex) quadratic program (QP) on the form: More... | |
bool | SolveQP (const Eigen::MatrixXd &_Q, const Eigen::VectorXd &_c, const Eigen::MatrixXd &_E_eq, const Eigen::VectorXd &_f_eq, const Eigen::MatrixXd &_E_ineq, const Eigen::VectorXd &_f_ineq, Eigen::VectorXd &_sol, const SolverType &_solver=SolverType::UNSPECIFIED, const int &_v=0) |
The SolveQP function solves a (convex) quadratic program (QP) on the form: More... | |
void | PublishTorqueMsg (const Eigen::Matrix< double, 12, 1 > &_desired_tau) |
The PublishTorqueMsg function publishes a desired torque message to the ROS topic set by the joint state publisher. More... | |
void | OnGenCoordMsg (const std_msgs::Float64MultiArrayConstPtr &_msg) |
The OnGenCoordMsg function handles an incoming generalized coordinates message from ROS. More... | |
void | OnGenVelMsg (const std_msgs::Float64MultiArrayConstPtr &_msg) |
The OnGenVelMsg function handles an incoming generalized velocities message from ROS. More... | |
void | OnContactStateMsg (const std_msgs::Int8MultiArrayConstPtr &_msg) |
The OnContactStateMsg function handles an incoming contact state message from ROS. More... | |
void | ProcessQueueThread () |
The ProcessQueueThread function is a ROS helper function that processes messages. More... | |
void | PublishQueueThread () |
The PublishQueueThread function is a ROS helper function that publish state messages. More... | |
Public Attributes | |
Kinematics | kinematics |
Kinematics. More... | |
Protected Member Functions | |
void | InitRos () |
The InitRos function is called to initialize ROS. More... | |
void | InitRosQueueThreads () |
The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads. More... | |
Private Attributes | |
Eigen::Matrix< double, 18, 1 > | genCoord |
Generalized Coordinates. More... | |
Eigen::Matrix< double, 18, 1 > | genVel |
Generalized Velocities. More... | |
Eigen::Matrix< Eigen::Vector3d, 4, 1 > | fPos |
Foot-point positions. More... | |
Eigen::Matrix< Eigen::Vector3d, 4, 1 > | fVel |
Foot-point velocities. More... | |
int | contactState [4] |
Contact State. More... | |
std::unique_ptr< ros::NodeHandle > | rosNode |
Node used for ROS transport. More... | |
ros::Subscriber | genCoordSub |
ROS Generalized Coordinates Subscriber. More... | |
ros::Subscriber | genVelSub |
ROS Generalized Coordinates Subscriber. More... | |
ros::Subscriber | contactStateSub |
ROS Contact State Subscriber. More... | |
ros::Publisher | jointStatePub |
ROS Joint State Publisher. More... | |
ros::Publisher | basePoseCmdPub |
ROS Base Position Command Publisher. More... | |
ros::Publisher | baseTwistCmdPub |
ROS Base Position Command Publisher. More... | |
ros::CallbackQueue | rosProcessQueue |
ROS callbackque that helps process messages. More... | |
ros::CallbackQueue | rosPublishQueue |
ROS callbackque that helps publish messages. More... | |
std::thread | rosProcessQueueThread |
Thread running the rosProcessQueue. More... | |
std::thread | rosPublishQueueThread |
Thread running the rosPublishQueue. More... | |
A class for hierarchical optimization control.
Definition at line 64 of file hierarchical_optimization_controller.h.
Drake Solver type enumerator.
Enumerator | |
---|---|
OSQP | |
ECQP | |
CLP | |
SCS | |
SNOPT | |
UNSPECIFIED |
Definition at line 77 of file hierarchical_optimization_controller.h.
Leg type enumerator.
Enumerator | |
---|---|
frontLeft | |
frontRight | |
rearLeft | |
rearRight | |
NONE |
Definition at line 80 of file hierarchical_optimization_controller.h.
Body type enumerator.
Enumerator | |
---|---|
base | |
hip | |
thigh | |
leg | |
foot |
Definition at line 83 of file hierarchical_optimization_controller.h.
HierarchicalOptimizationControl::HierarchicalOptimizationControl | ( | ) |
Constructor.
Definition at line 30 of file hierarchical_optimization_controller.cpp.
|
virtual |
Destructor.
Definition at line 46 of file hierarchical_optimization_controller.cpp.
void HierarchicalOptimizationControl::StaticTorqueTest | ( | ) |
Definition at line 60 of file hierarchical_optimization_controller.cpp.
void HierarchicalOptimizationControl::HeightRollYawTest | ( | ) |
Definition at line 154 of file hierarchical_optimization_controller.cpp.
Eigen::Matrix< double, 12, 1 > HierarchicalOptimizationControl::HierarchicalOptimization | ( | const Eigen::Matrix< double, 3, 1 > & | _desired_base_pos, |
const Eigen::Matrix< double, 3, 1 > & | _desired_base_vel, | ||
const Eigen::Matrix< double, 3, 1 > & | _desired_base_acc, | ||
const Eigen::Matrix< double, 3, 1 > & | _desired_base_ori, | ||
const Eigen::Matrix< Eigen::Vector3d, 4, 1 > & | _desired_f_pos, | ||
const Eigen::Matrix< Eigen::Vector3d, 4, 1 > & | _desired_f_vel, | ||
const Eigen::Matrix< Eigen::Vector3d, 4, 1 > & | _desired_f_acc, | ||
const Eigen::Matrix< Eigen::Vector3d, 4, 1 > & | _f_pos, | ||
const Eigen::Matrix< Eigen::Vector3d, 4, 1 > & | _f_vel, | ||
const Eigen::Matrix< double, 18, 1 > & | _q, | ||
const Eigen::Matrix< double, 18, 1 > & | _u, | ||
const int & | _v = 0 |
||
) |
The HierarchicalOptimization function finds the optimal joint torques for a desired motion plan. It finds joint torques by finding optimal joint accelerations and contact forces for a set of whole-body control QP tasks, and leveraging inverse dynamics.
[in] | _desired_base_pos | Desired base position. |
[in] | _desired_base_vel | Desired base velocity. |
[in] | _desired_base_acc | Desired base acceleration. |
[in] | _desired_base_ori | Desired base orientation. |
[in] | _desired_f_pos | Desired foot-point positions. |
[in] | _desired_f_vel | Desired foot-point velocities. |
[in] | _desired_f_acc | Desired foot-point accelerations. |
[in] | _f_pos | Foot-point positions. |
[in] | _f_vel | Foot-point velocities. |
[in] | _v | Verbosity level [0,1,2,3]. |
Definition at line 266 of file hierarchical_optimization_controller.cpp.
Eigen::Matrix< double, Eigen::Dynamic, 1 > HierarchicalOptimizationControl::HierarchicalQPOptimization | ( | const int & | _state_dim, |
const std::vector< Task > & | _tasks, | ||
const SolverType & | _solver = SolverType::OSQP , |
||
const int & | _v = 0 |
||
) |
The HierarchicalQPOptimization function finds the optimal solution for a set of tasks in a strictly prioritized order. The method iterates through the set of tasks and searches for a new solution in the null-space of all higher priority equality constraints. At each iteration a QP problem is solved to find a vector lying in the row-space of the null-space of all equality constraints, which improve on the current solution.
[in] | _state_dim | State dimension for the solution vector. |
[in] | _tasks | A set of tasks to be solved. |
[in] | _solver | Solver type. |
[in] | _v | Verbosity level [0,1,2,3]. |
Definition at line 679 of file hierarchical_optimization_controller.cpp.
Eigen::Matrix< double, Eigen::Dynamic, 1 > HierarchicalOptimizationControl::HierarchicalLeastSquareOptimization | ( | const Eigen::Matrix< Eigen::MatrixXd, Eigen::Dynamic, 1 > & | _A, |
const Eigen::Matrix< Eigen::Matrix< double, Eigen::Dynamic, 1 >, Eigen::Dynamic, 1 > & | _b, | ||
const int & | _v = 0 |
||
) |
The HierarchicalLeastSquareOptimization function finds the optimal solution for a set of linear equality constraints in a strictly prioritized order. The method iterates through the set of equality constraints and searches for a new solution in the null-space of all higher priority equality constraints. At each iteration the Moore-Penrose pseudoinverse is utilized to find a vector lying in the row-space of the null-space of all equality constraints, which improve on the current solution. The usage of the Moore-Penrose pseudoinverse yield a least square solution of the problem at hand.
[in] | _A | A set of equality constraint matrices A. |
[in] | _b | A set of equality constraint vectors b. |
[in] | _v | Verbosity level [0,1]. |
Definition at line 880 of file hierarchical_optimization_controller.cpp.
bool HierarchicalOptimizationControl::SolveQP | ( | const Eigen::MatrixXd & | _Q, |
const Eigen::VectorXd & | _c, | ||
const Eigen::MatrixXd & | _E_ineq, | ||
const Eigen::VectorXd & | _f_ineq, | ||
Eigen::VectorXd & | _sol, | ||
const SolverType & | _solver = SolverType::UNSPECIFIED , |
||
const int & | _v = 0 |
||
) |
The SolveQP function solves a (convex) quadratic program (QP) on the form:
min_x 0.5 x^T Q x + c^T x s.t. E_ineq x <= f_ineq
The toolbox uses the Drake toolbox for solving the problem. Currently Drake identifies the problem and chooses an appropriate commercial solver, but the solver can be specified (among the supported) by the user if one desires.
[in] | _Q | Cost matrix Q (must be positive semidefinite). |
[in] | _c | Cost vector c. |
[in] | _E_ineq | Linear inequality constraint matrix E_ineq; |
[in] | _f_ineq | Linear inequality constraint vector f_ineq; |
[out] | _sol | Solution of the QP (if it exists). |
[in] | _solver | Solver type, default is unspecified (Drake will choose accordingly). |
[in] | _v | Verbosity level. // TODO Update after verbosity is set |
Definition at line 958 of file hierarchical_optimization_controller.cpp.
bool HierarchicalOptimizationControl::SolveQP | ( | const Eigen::MatrixXd & | _Q, |
const Eigen::VectorXd & | _c, | ||
const Eigen::MatrixXd & | _A, | ||
const Eigen::VectorXd & | _lb, | ||
const Eigen::VectorXd & | _ub, | ||
Eigen::VectorXd & | _sol, | ||
const SolverType & | _solver = SolverType::UNSPECIFIED , |
||
const int & | _v = 0 |
||
) |
The SolveQP function solves a (convex) quadratic program (QP) on the form:
min_x 0.5 x^T Q x + c^T x s.t. lb <= A x <= ub
The toolbox uses the Drake toolbox for solving the problem. Currently Drake identifies the problem and chooses an appropriate commercial solver, but the solver can be specified (among the supported) by the user if one desires.
[in] | _Q | Cost matrix Q (must be positive semidefinite). |
[in] | _c | Cost vector c. |
[in] | _A | Linear inequality constraint matrix A; |
[in] | _lb | Linear inequality constraint lower bound vector; |
[in] | _ub | Linear inequality constraint upper bound vector; |
[out] | _sol | Solution of the QP (if it exists). |
[in] | _solver | Solver type, default is unspecified (Drake will choose accordingly). |
[in] | _v | Verbosity level. // TODO Update after verbosity is set |
Definition at line 985 of file hierarchical_optimization_controller.cpp.
bool HierarchicalOptimizationControl::SolveQP | ( | const Eigen::MatrixXd & | _Q, |
const Eigen::VectorXd & | _c, | ||
const Eigen::MatrixXd & | _E_eq, | ||
const Eigen::VectorXd & | _f_eq, | ||
const Eigen::MatrixXd & | _E_ineq, | ||
const Eigen::VectorXd & | _f_ineq, | ||
Eigen::VectorXd & | _sol, | ||
const SolverType & | _solver = SolverType::UNSPECIFIED , |
||
const int & | _v = 0 |
||
) |
The SolveQP function solves a (convex) quadratic program (QP) on the form:
min_x 0.5 x^T Q x + c^T x s.t. E_eq x = f_eq E_ineq x <= f_ineq
The toolbox uses the Drake toolbox for solving the problem. Currently Drake identifies the problem and chooses an appropriate commercial solver, but the solver can be specified (among the supported) by the user if one desires.
[in] | _Q | Cost matrix Q (must be positive semidefinite). |
[in] | _c | Cost vector c. |
[in] | _E_eq | Linear equality constraint matrix E_eq; |
[in] | _f_eq | Linear equality constraint vector f_eq; |
[in] | _E_ineq | Linear inequality constraint matrix E_ineq; |
[in] | _f_ineq | Linear inequality constraint vector f_ineq; |
[out] | _sol | Solution of the QP (if it exists). |
[in] | _solver | Solver type, default is unspecified (Drake will choose accordingly). |
[in] | _v | Verbosity level. // TODO Update after verbosity is set |
Definition at line 1120 of file hierarchical_optimization_controller.cpp.
void HierarchicalOptimizationControl::PublishTorqueMsg | ( | const Eigen::Matrix< double, 12, 1 > & | _desired_tau | ) |
The PublishTorqueMsg function publishes a desired torque message to the ROS topic set by the joint state publisher.
[in] | _desired_tau | Desired torque to be published. |
Definition at line 1220 of file hierarchical_optimization_controller.cpp.
void HierarchicalOptimizationControl::OnGenCoordMsg | ( | const std_msgs::Float64MultiArrayConstPtr & | _msg | ) |
The OnGenCoordMsg function handles an incoming generalized coordinates message from ROS.
[in] | _msg | A float array containing the generalized coordinates. |
Definition at line 1256 of file hierarchical_optimization_controller.cpp.
void HierarchicalOptimizationControl::OnGenVelMsg | ( | const std_msgs::Float64MultiArrayConstPtr & | _msg | ) |
The OnGenVelMsg function handles an incoming generalized velocities message from ROS.
[in] | _msg | A float array containing the generalized velocities. |
Definition at line 1273 of file hierarchical_optimization_controller.cpp.
void HierarchicalOptimizationControl::OnContactStateMsg | ( | const std_msgs::Int8MultiArrayConstPtr & | _msg | ) |
The OnContactStateMsg function handles an incoming contact state message from ROS.
[in] | _msg | A float array containing the contact state. |
Definition at line 1288 of file hierarchical_optimization_controller.cpp.
void HierarchicalOptimizationControl::ProcessQueueThread | ( | ) |
The ProcessQueueThread function is a ROS helper function that processes messages.
Definition at line 1305 of file hierarchical_optimization_controller.cpp.
void HierarchicalOptimizationControl::PublishQueueThread | ( | ) |
The PublishQueueThread function is a ROS helper function that publish state messages.
Definition at line 1315 of file hierarchical_optimization_controller.cpp.
|
protected |
The InitRos function is called to initialize ROS.
Definition at line 1325 of file hierarchical_optimization_controller.cpp.
|
protected |
The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads.
Definition at line 1412 of file hierarchical_optimization_controller.cpp.
Kinematics HierarchicalOptimizationControl::kinematics |
Definition at line 299 of file hierarchical_optimization_controller.h.
|
private |
Generalized Coordinates.
Definition at line 302 of file hierarchical_optimization_controller.h.
|
private |
Generalized Velocities.
Definition at line 305 of file hierarchical_optimization_controller.h.
|
private |
Foot-point positions.
Definition at line 308 of file hierarchical_optimization_controller.h.
|
private |
Foot-point velocities.
Definition at line 311 of file hierarchical_optimization_controller.h.
|
private |
Contact State.
Definition at line 314 of file hierarchical_optimization_controller.h.
|
private |
Node used for ROS transport.
Definition at line 317 of file hierarchical_optimization_controller.h.
|
private |
ROS Generalized Coordinates Subscriber.
Definition at line 320 of file hierarchical_optimization_controller.h.
|
private |
ROS Generalized Coordinates Subscriber.
Definition at line 323 of file hierarchical_optimization_controller.h.
|
private |
ROS Contact State Subscriber.
Definition at line 326 of file hierarchical_optimization_controller.h.
|
private |
ROS Joint State Publisher.
Definition at line 329 of file hierarchical_optimization_controller.h.
|
private |
ROS Base Position Command Publisher.
Definition at line 333 of file hierarchical_optimization_controller.h.
|
private |
ROS Base Position Command Publisher.
Definition at line 337 of file hierarchical_optimization_controller.h.
|
private |
ROS callbackque that helps process messages.
Definition at line 340 of file hierarchical_optimization_controller.h.
|
private |
ROS callbackque that helps publish messages.
Definition at line 343 of file hierarchical_optimization_controller.h.
|
private |
Thread running the rosProcessQueue.
Definition at line 346 of file hierarchical_optimization_controller.h.
|
private |
Thread running the rosPublishQueue.
Definition at line 349 of file hierarchical_optimization_controller.h.