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);
70 dynamicgraph::Vector);
75 dynamicgraph::Vector);
77 dynamicgraph::Vector);
80 dynamicgraph::Vector);
83 dynamicgraph::Vector);
95 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';
#define SOTADMITTANCECONTROLLER_EXPORT
void sendMsg(const std::string &msg, MsgType t=MSG_TYPE_INFO, const char *="", int=0)
tsid::math::Vector m_dq_fd
integral of the velocity error
DECLARE_SIGNAL_IN(force_integral_deadzone, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(force_integral_saturation, dynamicgraph::Vector)
RobotUtilShrPtr m_robot_util
DECLARE_SIGNAL_OUT(vDesRightFoot, dynamicgraph::Vector)
dqDes = J^+ * Kf * (fRef-f)
DECLARE_SIGNAL_IN(encoders, dynamicgraph::Vector)
DECLARE_SIGNAL_OUT(u, dynamicgraph::Vector)
damping factors used for the 4 end-effectors
bool m_useJacobianTranspose
true if the entity has been successfully initialized
DECLARE_SIGNAL_IN(fRightFootRef, dynamicgraph::Vector)
tsid::math::Vector m_dqErrIntegral
DECLARE_SIGNAL_IN(damping, dynamicgraph::Vector)
mask with 1 for controlled joints, 0 otherwise
DECLARE_SIGNAL_IN(fLeftFootFiltered, dynamicgraph::Vector)
6d estimated force filtered
tsid::math::Vector6 m_f_LF
desired 6d wrench right foot
DECLARE_SIGNAL_IN(ki_force, dynamicgraph::Vector)
tsid::math::Vector m_v_urdf
DECLARE_SIGNAL_IN(jointsVelocities, dynamicgraph::Vector)
Eigen::ColPivHouseholderQR< Matrix6x > m_J_LF_QR
int m_frame_id_lf
frame id of right foot
Eigen::ColPivHouseholderQR< Matrix6x > m_J_RF_QR
tsid::robots::RobotWrapper * m_robot
frame id of left foot
DECLARE_SIGNAL_IN(fRightFoot, dynamicgraph::Vector)
6d reference force
DECLARE_SIGNAL_OUT(vDesLeftFoot, dynamicgraph::Vector)
tsid::math::Vector6 m_f_RF
tsid::math::Vector m_qPrev
joint velocities computed with finite differences
DECLARE_SIGNAL_OUT(dqDes, dynamicgraph::Vector)
control
DECLARE_SIGNAL_IN(ki_vel, dynamicgraph::Vector)
tsid::math::Vector m_q_urdf
desired 6d wrench left foot
tsid::math::Vector6 m_v_RF_int
bool m_firstIter
control (i.e. motor currents)
DECLARE_SIGNAL_IN(fRightFootFiltered, dynamicgraph::Vector)
6d estimated force
DECLARE_SIGNAL_IN(kp_vel, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(kp_force, dynamicgraph::Vector)
tsid::math::Vector6 m_v_LF_int
int m_nj
control loop time period
tsid::math::Vector m_dq_des_urdf
DECLARE_SIGNAL_IN(controlledJoints, dynamicgraph::Vector)
6d estimated force filtered
pinocchio::Data::Matrix6x Matrix6x
previous value of encoders
DECLARE_SIGNAL_IN(fLeftFoot, dynamicgraph::Vector)
6d estimated force
DECLARE_SIGNAL_IN(fLeftFootRef, dynamicgraph::Vector)
6d reference force
int m_frame_id_rf
robot geometric/inertial data
AdmittanceController EntityClassName
Eigen::Matrix< double, 6, 1 > Vector6