19 #include <dynamic-graph/all-commands.h>
20 #include <dynamic-graph/factory.h>
23 #include <pinocchio/algorithm/frames.hpp>
24 #include <pinocchio/algorithm/kinematics.hpp>
25 #include <pinocchio/parsers/urdf.hpp>
26 #include <sot/core/debug.hh>
27 #include <sot/core/stop-watch.hh>
31 namespace talos_balance {
32 namespace dg = ::dynamicgraph;
34 using namespace dg::command;
37 #define PROFILE_SIMPLE_DISTRIBUTE_WRENCH_KINEMATICS_COMPUTATIONS \
38 "SimpleDistributeWrench: kinematics computations "
39 #define PROFILE_SIMPLE_DISTRIBUTE_WRENCH_WRENCHES_COMPUTATIONS \
40 "SimpleDistributeWrench: wrenches computations "
42 #define INPUT_SIGNALS m_wrenchDesSIN << m_qSIN << m_rhoSIN << m_phaseSIN
44 #define INNER_SIGNALS m_kinematics_computations << m_wrenches
46 #define OUTPUT_SIGNALS \
47 m_wrenchLeftSOUT << m_ankleWrenchLeftSOUT << m_surfaceWrenchLeftSOUT \
48 << m_copLeftSOUT << m_wrenchRightSOUT \
49 << m_ankleWrenchRightSOUT << m_surfaceWrenchRightSOUT \
50 << m_copRightSOUT << m_wrenchRefSOUT << m_zmpRefSOUT \
51 << m_emergencyStopSOUT
59 "SimpleDistributeWrench");
68 CONSTRUCT_SIGNAL_IN(rho, double),
69 CONSTRUCT_SIGNAL_IN(phase, int),
70 CONSTRUCT_SIGNAL_INNER(kinematics_computations, int, m_qSIN),
71 CONSTRUCT_SIGNAL_INNER(wrenches, int,
72 m_wrenchDesSIN << m_rhoSIN << m_phaseSIN
73 << m_kinematics_computationsSINNER),
87 m_wrenchLeftSOUT << m_wrenchRightSOUT),
89 CONSTRUCT_SIGNAL_OUT(emergencyStop, bool, m_zmpRefSOUT),
90 m_initSucceeded(false),
92 m_data(pinocchio::Model()) {
97 docCommandVoid1(
"Initialize the entity.",
102 if (!m_wrenchDesSIN.isPlugged())
103 return SEND_MSG(
"Init failed: signal wrenchDes is not plugged",
105 if (!m_qSIN.isPlugged())
106 return SEND_MSG(
"Init failed: signal q is not plugged", MSG_TYPE_ERROR);
111 if (isNameInRobotUtil(localName)) {
115 SEND_MSG(
"You should have a robotUtil pointer initialized before",
120 pinocchio::urdf::buildModel(
m_robot_util->m_urdf_filename,
121 pinocchio::JointModelFreeFlyer(),
m_model);
123 }
catch (
const std::exception& e) {
124 std::cout << e.what();
125 SEND_MSG(
"Init failed: Could load URDF :" +
m_robot_util->m_urdf_filename,
140 pinocchio::SE3(Eigen::Matrix3d::Identity(),
141 m_robot_util->m_foot_util.m_Right_Foot_Sole_XYZ.head<3>());
147 const dg::Vector& wrenchGlobal,
const pinocchio::SE3& pose)
const {
149 pose.actInv(pinocchio::Force(wrenchGlobal)).toVector();
151 const double h = pose.translation()[2];
153 const double fx =
wrench[0];
154 const double fy =
wrench[1];
155 const double fz =
wrench[2];
156 const double tx =
wrench[3];
157 const double ty =
wrench[4];
163 if (fz >= m_eps / 2) {
164 px = (-ty - fx *
h) / fz;
165 py = (tx - fy *
h) / fz;
170 const double pz = 0.0;
185 if (!m_initSucceeded) {
186 SEND_WARNING_STREAM_MSG(
187 "Cannot compute signal kinematics_computations before initialization!");
191 const Eigen::VectorXd&
q = m_qSIN(iter);
192 assert(
q.size() == m_model.nq &&
"Unexpected size of signal q");
196 pinocchio::forwardKinematics(m_model, m_data,
q);
197 pinocchio::updateFramePlacement(m_model, m_data, m_left_foot_id);
198 pinocchio::updateFramePlacement(m_model, m_data, m_right_foot_id);
200 m_contactLeft = m_data.oMf[m_left_foot_id] * m_ankle_M_sole;
201 m_contactRight = m_data.oMf[m_right_foot_id] * m_ankle_M_sole;
210 Eigen::Vector3d forceLeft = wrenchDes.head<3>() / 2;
211 Eigen::Vector3d forceRight = forceLeft;
212 forceLeft[2] = rho * wrenchDes[2];
213 forceRight[2] = (1 - rho) * wrenchDes[2];
215 Eigen::Vector3d tauLeft =
m_contactLeft.translation().cross(forceLeft);
216 Eigen::Vector3d tauRight =
m_contactRight.translation().cross(forceRight);
218 Eigen::Vector3d tauResidual = (wrenchDes.tail<3>() - tauLeft - tauRight) / 2;
219 tauLeft += tauResidual;
220 tauRight += tauResidual;
225 const bool success =
true;
232 const bool success =
true;
236 const Eigen::VectorXd& result = wrenchDes;
241 }
else if (phase < 0) {
248 if (!m_initSucceeded) {
249 SEND_WARNING_STREAM_MSG(
250 "Cannot compute signal wrenches before initialization!");
254 const Eigen::VectorXd& wrenchDes = m_wrenchDesSIN(iter);
255 const int& dummy = m_kinematics_computationsSINNER(iter);
257 const int& phase = m_phaseSIN(iter);
259 assert(wrenchDes.size() == 6 &&
"Unexpected size of signal wrenchDes");
264 const double& rho = m_rhoSIN(iter);
266 distributeWrench(wrenchDes, rho);
268 saturateWrench(wrenchDes, phase);
273 if (m_emergency_stop_triggered) {
274 SEND_WARNING_STREAM_MSG(
"Error in wrench distribution!");
282 if (!m_initSucceeded) {
283 SEND_WARNING_STREAM_MSG(
284 "Cannot compute signal wrenchLeft before initialization!");
287 if (s.size() != 6) s.resize(6);
289 const int& dummy = m_wrenchesSINNER(iter);
296 if (!m_initSucceeded) {
297 SEND_WARNING_STREAM_MSG(
298 "Cannot compute signal wrenchRight before initialization!");
301 if (s.size() != 6) s.resize(6);
303 const int& dummy = m_wrenchesSINNER(iter);
310 if (!m_initSucceeded) {
311 SEND_WARNING_STREAM_MSG(
312 "Cannot compute signal ankleWrenchLeft before initialization!");
315 if (s.size() != 6) s.resize(6);
317 const Eigen::VectorXd& wrenchLeft = m_wrenchLeftSOUT(iter);
319 s = m_data.oMf[m_left_foot_id]
320 .actInv(pinocchio::Force(wrenchLeft))
327 if (!m_initSucceeded) {
328 SEND_WARNING_STREAM_MSG(
329 "Cannot compute signal ankleWrenchRight before initialization!");
332 if (s.size() != 6) s.resize(6);
334 const Eigen::VectorXd& wrenchRight = m_wrenchRightSOUT(iter);
336 s = m_data.oMf[m_right_foot_id]
337 .actInv(pinocchio::Force(wrenchRight))
344 if (!m_initSucceeded) {
345 SEND_WARNING_STREAM_MSG(
346 "Cannot compute signal surfaceWrenchLeft before initialization!");
349 if (s.size() != 6) s.resize(6);
351 const Eigen::VectorXd& wrenchLeft = m_wrenchLeftSOUT(iter);
353 s = m_contactLeft.actInv(pinocchio::Force(wrenchLeft)).toVector();
359 if (!m_initSucceeded) {
360 SEND_WARNING_STREAM_MSG(
361 "Cannot compute signal surfaceWrenchRight before initialization!");
364 if (s.size() != 6) s.resize(6);
366 const Eigen::VectorXd& wrenchRight = m_wrenchRightSOUT(iter);
368 s = m_contactRight.actInv(pinocchio::Force(wrenchRight)).toVector();
374 if (!m_initSucceeded) {
375 SEND_WARNING_STREAM_MSG(
376 "Cannot compute signal copLeft before initialization!");
379 if (s.size() != 3) s.resize(3);
381 const Eigen::VectorXd& wrenchLeft = m_wrenchLeftSOUT(iter);
383 if (m_emergency_stop_triggered) {
388 s = computeCoP(wrenchLeft, m_contactLeft);
394 if (!m_initSucceeded) {
395 SEND_WARNING_STREAM_MSG(
396 "Cannot compute signal copRight before initialization!");
399 if (s.size() != 3) s.resize(3);
401 const Eigen::VectorXd& wrenchRight = m_wrenchRightSOUT(iter);
403 if (m_emergency_stop_triggered) {
408 s = computeCoP(wrenchRight, m_contactRight);
414 if (!m_initSucceeded) {
415 SEND_WARNING_STREAM_MSG(
416 "Cannot compute signal wrenchRef before initialization!");
419 if (s.size() != 6) s.resize(6);
421 const Eigen::VectorXd& wrenchLeft = m_wrenchLeftSOUT(iter);
422 const Eigen::VectorXd& wrenchRight = m_wrenchRightSOUT(iter);
424 s = wrenchLeft + wrenchRight;
430 if (!m_initSucceeded) {
431 SEND_WARNING_STREAM_MSG(
432 "Cannot compute signal zmpRef before initialization!");
435 if (s.size() != 3) s.resize(3);
437 const Eigen::VectorXd& wrenchRef = m_wrenchRefSOUT(iter);
439 if (m_emergency_stop_triggered) {
446 const double fz = wrenchRef[2];
447 const double tx = wrenchRef[3];
448 const double ty = wrenchRef[4];
453 if (fz >= m_eps / 2) {
460 const double pz = 0.0;
462 Eigen::Vector3d zmp(3);
476 s = m_emergency_stop_triggered;
487 os <<
"SimpleDistributeWrench " << getName();
489 getProfiler().report_all(3, os);
490 }
catch (ExceptionSignal e) {
pinocchio::FrameIndex m_left_foot_id
ankle to sole transformation
RobotUtilShrPtr m_robot_util
Pinocchio robot data.
Eigen::Vector3d computeCoP(const dynamicgraph::Vector &wrench, const pinocchio::SE3 &pose) const
Eigen::Matrix< double, 6, 1 > m_wrenchLeft
virtual void display(std::ostream &os) const
pinocchio::SE3 m_contactLeft
void init(const std::string &robotName)
pinocchio::SE3 m_contactRight
pinocchio::Model m_model
true if the entity has been successfully initialized
Eigen::Matrix< double, 6, 1 > m_wrenchRight
void distributeWrench(const Eigen::VectorXd &wrenchDes, const double rho)
pinocchio::SE3 m_ankle_M_sole
bool m_emergency_stop_triggered
pinocchio::FrameIndex m_right_foot_id
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SimpleDistributeWrench(const std::string &name)
void saturateWrench(const Eigen::VectorXd &wrenchDes, const int phase)
pinocchio::Data m_data
Pinocchio robot model.
Eigen::Matrix< Scalar, 6, 1 > Vector6
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
AdmittanceControllerEndEffector EntityClassName
DEFINE_SIGNAL_OUT_FUNCTION(dq, dynamicgraph::Vector)
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AdmittanceControllerEndEffector, "AdmittanceControllerEndEffector")
DEFINE_SIGNAL_INNER_FUNCTION(w_force, dynamicgraph::Vector)
#define PROFILE_SIMPLE_DISTRIBUTE_WRENCH_WRENCHES_COMPUTATIONS
#define PROFILE_SIMPLE_DISTRIBUTE_WRENCH_KINEMATICS_COMPUTATIONS