| Line |
Branch |
Exec |
Source |
| 1 |
|
|
// |
| 2 |
|
|
// Copyright (c) 2025 CNRS INRIA LORIA |
| 3 |
|
|
// |
| 4 |
|
|
// This file is part of tsid |
| 5 |
|
|
// tsid is free software: you can redistribute it |
| 6 |
|
|
// and/or modify it under the terms of the GNU Lesser General Public |
| 7 |
|
|
// License as published by the Free Software Foundation, either version |
| 8 |
|
|
// 3 of the License, or (at your option) any later version. |
| 9 |
|
|
// tsid is distributed in the hope that it will be |
| 10 |
|
|
// useful, but WITHOUT ANY WARRANTY; without even the implied warranty |
| 11 |
|
|
// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU |
| 12 |
|
|
// General Lesser Public License for more details. You should have |
| 13 |
|
|
// received a copy of the GNU Lesser General Public License along with |
| 14 |
|
|
// tsid If not, see |
| 15 |
|
|
// <http://www.gnu.org/licenses/>. |
| 16 |
|
|
// |
| 17 |
|
|
|
| 18 |
|
|
#include "tsid/contacts/measured-3d-force.hpp" |
| 19 |
|
|
|
| 20 |
|
|
#include "tsid/robots/robot-wrapper.hpp" |
| 21 |
|
|
|
| 22 |
|
|
namespace tsid { |
| 23 |
|
|
namespace contacts { |
| 24 |
|
|
|
| 25 |
|
|
using namespace std; |
| 26 |
|
|
using namespace math; |
| 27 |
|
|
using namespace pinocchio; |
| 28 |
|
|
|
| 29 |
|
|
typedef pinocchio::Data::Matrix6x Matrix6x; |
| 30 |
|
|
|
| 31 |
|
✗ |
Measured3Dforce::Measured3Dforce(const std::string &name, RobotWrapper &robot, |
| 32 |
|
✗ |
const std::string &frameName) |
| 33 |
|
✗ |
: MeasuredForceBase(name, robot), m_frame_name(frameName) { |
| 34 |
|
✗ |
assert(m_robot.model().existFrame(frameName)); |
| 35 |
|
✗ |
m_frame_id = m_robot.model().getFrameId(frameName); |
| 36 |
|
|
|
| 37 |
|
✗ |
m_fext.setZero(); |
| 38 |
|
✗ |
m_J.setZero(3, robot.nv()); |
| 39 |
|
✗ |
m_J_rotated.setZero(3, robot.nv()); |
| 40 |
|
✗ |
m_computedTorques.setZero(robot.nv()); |
| 41 |
|
|
|
| 42 |
|
✗ |
m_local_frame = true; |
| 43 |
|
|
} |
| 44 |
|
|
|
| 45 |
|
✗ |
const Vector &Measured3Dforce::computeJointTorques(Data &data) { |
| 46 |
|
✗ |
Matrix6x J; |
| 47 |
|
✗ |
J.setZero(6, m_robot.nv()); |
| 48 |
|
|
|
| 49 |
|
✗ |
m_robot.frameJacobianLocal(data, m_frame_id, J); |
| 50 |
|
✗ |
m_J = J.topRows(3); |
| 51 |
|
|
|
| 52 |
|
✗ |
if (!m_local_frame) { |
| 53 |
|
|
// Compute Jacobian in local world-oriented frame |
| 54 |
|
✗ |
SE3 oMi, oMi_rotation_only; |
| 55 |
|
✗ |
oMi_rotation_only.setIdentity(); |
| 56 |
|
✗ |
m_robot.framePosition(data, m_frame_id, oMi); |
| 57 |
|
✗ |
oMi_rotation_only.rotation(oMi.rotation()); |
| 58 |
|
|
|
| 59 |
|
|
// Use an explicit temporary `m_J_rotated` here to avoid allocations. |
| 60 |
|
✗ |
m_J_rotated.noalias() = (oMi_rotation_only.toActionMatrix() * J).topRows(3); |
| 61 |
|
✗ |
m_J = m_J_rotated; |
| 62 |
|
|
} |
| 63 |
|
|
|
| 64 |
|
✗ |
m_computedTorques = m_J.transpose() * m_fext; |
| 65 |
|
|
|
| 66 |
|
✗ |
return m_computedTorques; |
| 67 |
|
|
} |
| 68 |
|
|
|
| 69 |
|
✗ |
void Measured3Dforce::setMeasuredContactForce(const Vector3 &fext) { |
| 70 |
|
✗ |
m_fext = fext; |
| 71 |
|
|
} |
| 72 |
|
|
|
| 73 |
|
✗ |
const Vector3 &Measured3Dforce::getMeasuredContactForce() const { |
| 74 |
|
✗ |
return m_fext; |
| 75 |
|
|
} |
| 76 |
|
|
|
| 77 |
|
✗ |
void Measured3Dforce::useLocalFrame(bool local_frame) { |
| 78 |
|
✗ |
m_local_frame = local_frame; |
| 79 |
|
|
} |
| 80 |
|
|
|
| 81 |
|
|
} // namespace contacts |
| 82 |
|
|
} // namespace tsid |
| 83 |
|
|
|