Line |
Branch |
Exec |
Source |
1 |
|
|
// |
2 |
|
|
// Copyright (c) 2022 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-6Dwrench.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 |
|
✗ |
Measured6Dwrench::Measured6Dwrench(const std::string &name, RobotWrapper &robot, |
30 |
|
✗ |
const std::string &frameName) |
31 |
|
✗ |
: MeasuredForceBase(name, robot), m_frame_name(frameName) { |
32 |
|
✗ |
assert(m_robot.model().existFrame(frameName)); |
33 |
|
✗ |
m_frame_id = m_robot.model().getFrameId(frameName); |
34 |
|
|
|
35 |
|
✗ |
m_fext.setZero(); |
36 |
|
✗ |
m_J.setZero(6, robot.nv()); |
37 |
|
✗ |
m_J_rotated.setZero(6, robot.nv()); |
38 |
|
✗ |
m_computedTorques.setZero(robot.nv()); |
39 |
|
|
|
40 |
|
✗ |
m_local_frame = true; |
41 |
|
|
} |
42 |
|
|
|
43 |
|
✗ |
const Vector &Measured6Dwrench::computeJointTorques(Data &data) { |
44 |
|
✗ |
m_robot.frameJacobianLocal(data, m_frame_id, m_J); |
45 |
|
|
|
46 |
|
✗ |
if (!m_local_frame) { |
47 |
|
|
// Compute Jacobian in local world-oriented frame |
48 |
|
✗ |
SE3 oMi, oMi_rotation_only; |
49 |
|
✗ |
oMi_rotation_only.setIdentity(); |
50 |
|
✗ |
m_robot.framePosition(data, m_frame_id, oMi); |
51 |
|
✗ |
oMi_rotation_only.rotation(oMi.rotation()); |
52 |
|
|
|
53 |
|
|
// Use an explicit temporary `m_J_rotated` here to avoid allocations. |
54 |
|
✗ |
m_J_rotated.noalias() = oMi_rotation_only.toActionMatrix() * m_J; |
55 |
|
✗ |
m_J = m_J_rotated; |
56 |
|
|
} |
57 |
|
|
|
58 |
|
✗ |
m_computedTorques = m_J.transpose() * m_fext; |
59 |
|
|
|
60 |
|
✗ |
return m_computedTorques; |
61 |
|
|
} |
62 |
|
|
|
63 |
|
✗ |
void Measured6Dwrench::setMeasuredContactForce(const Vector6 &fext) { |
64 |
|
✗ |
m_fext = fext; |
65 |
|
|
} |
66 |
|
|
|
67 |
|
✗ |
const Vector6 &Measured6Dwrench::getMeasuredContactForce() const { |
68 |
|
✗ |
return m_fext; |
69 |
|
|
} |
70 |
|
|
|
71 |
|
✗ |
void Measured6Dwrench::useLocalFrame(bool local_frame) { |
72 |
|
✗ |
m_local_frame = local_frame; |
73 |
|
|
} |
74 |
|
|
|
75 |
|
|
} // namespace contacts |
76 |
|
|
} // namespace tsid |
77 |
|
|
|