6 #ifndef __sot_torque_control_inverse_dynamics_balance_controller_H__
7 #define __sot_torque_control_inverse_dynamics_balance_controller_H__
14 #if defined(inverse_dynamics_balance_controller_EXPORTS)
15 #define SOTINVERSEDYNAMICSBALANCECONTROLLER_EXPORT __declspec(dllexport)
17 #define SOTINVERSEDYNAMICSBALANCECONTROLLER_EXPORT __declspec(dllimport)
20 #define SOTINVERSEDYNAMICSBALANCECONTROLLER_EXPORT
29 #include "boost/assign.hpp"
32 #include <pinocchio/multibody/model.hpp>
33 #include <pinocchio/parsers/urdf.hpp>
34 #include <tsid/contacts/contact-6d.hpp>
35 #include <tsid/formulations/inverse-dynamics-formulation-acc-force.hpp>
36 #include <tsid/robots/robot-wrapper.hpp>
37 #include <tsid/solvers/solver-HQP-base.hpp>
38 #include <tsid/tasks/task-com-equality.hpp>
39 #include <tsid/tasks/task-joint-posture.hpp>
40 #include <tsid/trajectories/trajectory-euclidian.hpp>
43 #include <dynamic-graph/signal-helper.h>
45 #include <sot/core/matrix-geometry.hh>
46 #include <sot/core/robot-utils.hh>
60 DYNAMIC_GRAPH_ENTITY_DECL();
63 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
68 void init(
const double& dt,
const std::string& robotRef);
69 void updateComOffset();
70 void removeRightFootContact(
const double& transitionTime);
71 void removeLeftFootContact(
const double& transitionTime);
72 void addRightFootContact(
const double& transitionTime);
73 void addLeftFootContact(
const double& transitionTime);
74 void addTaskRightHand();
75 void removeTaskRightHand(
const double& transitionTime);
76 void addTaskLeftHand();
77 void removeTaskLeftHand(
const double& transitionTime);
153 dynamicgraph::Vector);
195 virtual void display(std::ostream& os)
const;
197 void sendMsg(
const std::string& msg, MsgType t = MSG_TYPE_INFO,
198 const char* =
"",
int = 0) {
199 logger_.stream(t) << (
"[" + name +
"] " + msg) <<
'\n';
213 LEFT_SUPPORT_TRANSITION = 2,
215 RIGHT_SUPPORT_TRANSITION = 4
222 TASK_RIGHT_HAND_ON = 0,
224 TASK_RIGHT_HAND_OFF = 1
229 TASK_LEFT_HAND_ON = 0,
231 TASK_LEFT_HAND_OFF = 1
248 tsid::InverseDynamicsFormulationAccForce*
m_invDyn;
DECLARE_SIGNAL_OUT(zmp_des, dynamicgraph::Vector)
void sendMsg(const std::string &msg, MsgType t=MSG_TYPE_INFO, const char *="", int=0)
tsid::tasks::TaskComEquality * m_taskCom
DECLARE_SIGNAL_IN(rf_ref_vel, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(kp_com, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(base_orientation_ref_acc, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(w_posture, double)
LeftHandState m_leftHandState
DECLARE_SIGNAL_IN(f_ref_right_foot, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(w_hands, double)
DECLARE_SIGNAL_OUT(zmp_des_left_foot, dynamicgraph::Vector)
bool m_firstTime
True if controler is enabled.
tsid::math::Vector3 m_zmp_des
3d desired zmp left foot expressed in local frame
DECLARE_SIGNAL_OUT(zmp_des_left_foot_local, dynamicgraph::Vector)
tsid::math::Vector3 m_zmp
3d zmp left foot
DECLARE_SIGNAL_IN(f_max_left_foot, double)
tsid::tasks::TaskSE3Equality * m_taskLH
DECLARE_SIGNAL_IN(com_ref_pos, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(zmp_left_foot, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(rh_ref_pos, dynamicgraph::Vector)
tsid::math::Vector m_f
desired accelerations (urdf order)
tsid::solvers::SolverHQPBase * m_hqpSolver
DECLARE_SIGNAL_IN(kp_posture, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(f_des_left_foot, dynamicgraph::Vector)
tsid::tasks::TaskJointPosture * m_taskBlockedJoints
tsid::tasks::TaskSE3Equality * m_taskRF
DECLARE_SIGNAL_IN(lh_ref_vel, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(f_des_right_foot, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(right_hand_vel, dynamicgraph::Vector)
tsid::math::Vector3 m_zmp_RF
3d zmp left foot
DECLARE_SIGNAL_IN(kd_posture, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(right_hand_acc, dynamicgraph::Vector)
RobotUtilShrPtr m_robot_util
DECLARE_SIGNAL_IN(active_joints, dynamicgraph::Vector)
bool m_enabled
true if the entity has been successfully initialized
ContactState
True at the first iteration of the controller.
tsid::math::Vector m_dv_sot
double m_t
control loop time period
DECLARE_SIGNAL_OUT(zmp, dynamicgraph::Vector)
tsid::trajectories::TrajectorySample m_sampleRH
DECLARE_SIGNAL_IN(lh_ref_pos, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(ddq_max, dynamicgraph::Vector)
int m_frame_id_rh
frame id of left foot
DECLARE_SIGNAL_IN(w_feet, double)
DECLARE_SIGNAL_IN(dq_max, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(kd_pos, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(f_max_right_foot, double)
DECLARE_SIGNAL_OUT(com_acc, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(left_foot_acc_des, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(kp_constraints, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(left_hand_pos, dynamicgraph::Vector)
tsid::InverseDynamicsFormulationAccForce * m_invDyn
tsid::math::Vector3 m_zmp_des_RF
3d desired zmp left foot
DECLARE_SIGNAL_IN(rf_ref_pos, dynamicgraph::Vector)
int m_frame_id_lh
frame id of right hand
DECLARE_SIGNAL_IN(w_base_orientation, double)
DECLARE_SIGNAL_IN(base_orientation_ref_vel, dynamicgraph::Vector)
tsid::math::Vector6 m_f_LF
desired 6d wrench right foot
tsid::math::Vector m_v_urdf
DECLARE_SIGNAL_IN(q_max, dynamicgraph::Vector)
Eigen::ColPivHouseholderQR< Matrix6x > m_J_LF_QR
tsid::math::Vector3 m_zmp_LF
3d desired global zmp
DECLARE_SIGNAL_OUT(right_foot_acc, dynamicgraph::Vector)
int m_frame_id_lf
frame id of right foot
DECLARE_SIGNAL_OUT(com, dynamicgraph::Vector)
Eigen::ColPivHouseholderQR< Matrix6x > m_J_RF_QR
tsid::robots::RobotWrapper * m_robot
frame id of left hand
DECLARE_SIGNAL_IN(posture_ref_acc, dynamicgraph::Vector)
DECLARE_SIGNAL_INNER(active_joints_checked, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(base_orientation_ref_pos, dynamicgraph::Vector)
tsid::solvers::SolverHQPBase * m_hqpSolver_60_36_34
DECLARE_SIGNAL_OUT(base_orientation, dynamicgraph::Vector)
tsid::math::Vector6 m_f_RF
desired force coefficients (24d)
tsid::math::Vector m_tau_sot
3d global zmp
tsid::contacts::Contact6d * m_contactLH
DECLARE_SIGNAL_IN(lf_ref_vel, dynamicgraph::Vector)
tsid::math::Vector3 m_zmp_des_LF_local
3d desired zmp left foot
DECLARE_SIGNAL_OUT(tau_des, dynamicgraph::Vector)
mask with 1 for controlled joints, 0 otherwise
RightHandState m_rightHandState
DECLARE_SIGNAL_IN(q_min, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(kd_feet, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(zmp_ref, dynamicgraph::Vector)
tsid::math::Vector m_q_urdf
tsid::math::Vector3 m_zmp_des_RF_local
3d desired zmp left foot expressed in local frame
tsid::tasks::TaskSE3Equality * m_taskLF
DECLARE_SIGNAL_IN(posture_ref_vel, dynamicgraph::Vector)
tsid::trajectories::TrajectorySample m_sampleRF
tsid::math::Vector6 m_v_RF_int
double m_contactTransitionTime
DECLARE_SIGNAL_IN(kd_com, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(zmp_des_right_foot, dynamicgraph::Vector)
tsid::trajectories::TrajectorySample m_samplePosture
DECLARE_SIGNAL_OUT(right_foot_pos, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(zmp_des_right_foot_local, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(left_foot_vel, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(kp_pos, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(dv_des, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(kp_feet, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(rh_ref_vel, dynamicgraph::Vector)
tsid::trajectories::TrajectorySample m_sampleCom
DECLARE_SIGNAL_IN(contact_points, dynamicgraph::Matrix)
DECLARE_SIGNAL_IN(lf_ref_pos, dynamicgraph::Vector)
tsid::math::Vector m_dv_urdf
desired accelerations (sot order)
tsid::trajectories::TrajectorySample m_sampleLH
DECLARE_SIGNAL_IN(com_ref_vel, dynamicgraph::Vector)
tsid::contacts::Contact6d * m_contactRF
DECLARE_SIGNAL_OUT(left_foot_pos, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(right_foot_acc_des, dynamicgraph::Vector)
tsid::tasks::TaskSE3Equality * m_taskRH
tsid::contacts::Contact6d * m_contactLF
tsid::math::Vector3 m_com_offset
desired 6d wrench left foot
DECLARE_SIGNAL_OUT(left_foot_acc, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(zmp_right_foot, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(w_com, double)
tsid::math::Vector6 m_v_LF_int
DECLARE_SIGNAL_IN(posture_ref_pos, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(right_hand_pos, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(kd_base_orientation, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(rotor_inertias, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(q, dynamicgraph::Vector)
tsid::math::Vector3 m_zmp_des_LF
3d CoM offset
tsid::contacts::Contact6d * m_contactRH
DECLARE_SIGNAL_IN(wrench_right_foot, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(weight_contact_forces, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(kd_hands, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(kd_constraints, dynamicgraph::Vector)
pinocchio::Data::Matrix6x Matrix6x
DECLARE_SIGNAL_IN(lh_ref_acc, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(left_hand_vel, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(wrench_base, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(kp_base_orientation, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(kp_hands, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(w_torques, double)
DECLARE_SIGNAL_IN(rh_ref_acc, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(rf_ref_acc, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(f_min, double)
DECLARE_SIGNAL_IN(wrench_left_foot, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(right_foot_vel, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(mu, double)
DECLARE_SIGNAL_IN(contact_normal, dynamicgraph::Vector)
tsid::solvers::SolverHQPBase * m_hqpSolver_48_30_17
DECLARE_SIGNAL_OUT(M, dynamicgraph::Matrix)
DECLARE_SIGNAL_OUT(com_acc_des, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(gear_ratios, dynamicgraph::Vector)
tsid::trajectories::TrajectorySample m_sampleLF
DECLARE_SIGNAL_IN(tau_max, dynamicgraph::Vector)
ContactState m_contactState
DECLARE_SIGNAL_IN(f_ref_left_foot, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(left_hand_acc, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(w_forces, double)
DECLARE_SIGNAL_OUT(com_vel, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(com_ref_acc, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(dt_joint_pos_limits, double)
tsid::tasks::TaskJointPosture * m_taskPosture
DECLARE_SIGNAL_IN(v, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(lf_ref_acc, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(tau_estimated, dynamicgraph::Vector)
#define SOTINVERSEDYNAMICSBALANCECONTROLLER_EXPORT
AdmittanceController EntityClassName
Eigen::Matrix< double, 3, 1 > Vector3
Eigen::Matrix< double, 6, 1 > Vector6