6 #ifndef __sot_torque_control_admittance_controller_H__ 7 #define __sot_torque_control_admittance_controller_H__ 14 #if defined(sot_admittance_controller_EXPORTS) 15 #define SOTADMITTANCECONTROLLER_EXPORT __declspec(dllexport) 17 #define SOTADMITTANCECONTROLLER_EXPORT __declspec(dllimport) 20 #define SOTADMITTANCECONTROLLER_EXPORT 28 #include <tsid/robots/robot-wrapper.hpp> 29 #include <tsid/tasks/task-se3-equality.hpp> 31 #include "boost/assign.hpp" 34 #include <dynamic-graph/signal-helper.h> 36 #include <sot/core/matrix-geometry.hh> 37 #include <sot/core/robot-utils.hh> 48 :
public ::dynamicgraph::Entity {
50 DYNAMIC_GRAPH_ENTITY_DECL();
53 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
58 void init(
const double& dt,
const std::string& robotRef);
61 DECLARE_SIGNAL_IN(encoders, dynamicgraph::Vector);
62 DECLARE_SIGNAL_IN(jointsVelocities, dynamicgraph::Vector);
63 DECLARE_SIGNAL_IN(kp_force, dynamicgraph::Vector);
64 DECLARE_SIGNAL_IN(ki_force, dynamicgraph::Vector);
65 DECLARE_SIGNAL_IN(kp_vel, dynamicgraph::Vector);
66 DECLARE_SIGNAL_IN(ki_vel, dynamicgraph::Vector);
67 DECLARE_SIGNAL_IN(force_integral_saturation, dynamicgraph::Vector);
68 DECLARE_SIGNAL_IN(force_integral_deadzone, dynamicgraph::Vector);
69 DECLARE_SIGNAL_IN(fRightFootRef,
70 dynamicgraph::Vector);
71 DECLARE_SIGNAL_IN(fLeftFootRef, dynamicgraph::Vector);
72 DECLARE_SIGNAL_IN(fRightFoot, dynamicgraph::Vector);
73 DECLARE_SIGNAL_IN(fLeftFoot, dynamicgraph::Vector);
74 DECLARE_SIGNAL_IN(fRightFootFiltered,
75 dynamicgraph::Vector);
76 DECLARE_SIGNAL_IN(fLeftFootFiltered,
77 dynamicgraph::Vector);
80 dynamicgraph::Vector);
83 dynamicgraph::Vector);
92 DECLARE_SIGNAL_OUT(u, dynamicgraph::Vector);
94 DECLARE_SIGNAL_OUT(dqDes,
95 dynamicgraph::Vector);
96 DECLARE_SIGNAL_OUT(vDesRightFoot, dynamicgraph::Vector);
97 DECLARE_SIGNAL_OUT(vDesLeftFoot, dynamicgraph::Vector);
104 virtual void display(std::ostream& os)
const;
106 void sendMsg(
const std::string& msg, MsgType t = MSG_TYPE_INFO,
107 const char* =
"",
int = 0) {
108 logger_.stream(t) << (
"[" + name +
"] " + msg) <<
'\n';
168 #endif // #ifndef __sot_torque_control_admittance_controller_H__ bool m_firstIter
control (i.e. motor currents)
tsid::math::Vector6 m_v_LF_int
Eigen::ColPivHouseholderQR< Matrix6x > m_J_LF_QR
tsid::math::Vector m_qPrev
joint velocities computed with finite differences
bool m_useJacobianTranspose
true if the entity has been successfully initialized
tsid::math::Vector6 m_f_RF
tsid::math::Vector m_v_urdf
RobotUtilShrPtr m_robot_util
int m_frame_id_lf
frame id of right foot
tsid::math::Vector m_dq_fd
integral of the velocity error
tsid::math::Vector m_dqErrIntegral
int m_nj
control loop time period
tsid::math::Vector6 m_v_RF_int
tsid::math::Vector m_dq_des_urdf
int m_frame_id_rf
robot geometric/inertial data
Eigen::Matrix< double, 6, 1 > Vector6
tsid::robots::RobotWrapper * m_robot
frame id of left foot
pinocchio::Data::Matrix6x Matrix6x
previous value of encoders
tsid::math::Vector m_q_urdf
desired 6d wrench left foot
AdmittanceController EntityClassName
Eigen::ColPivHouseholderQR< Matrix6x > m_J_RF_QR
tsid::math::Vector6 m_f_LF
desired 6d wrench right foot
#define SOTADMITTANCECONTROLLER_EXPORT
void sendMsg(const std::string &msg, MsgType t=MSG_TYPE_INFO, const char *="", int=0)