src/contacts/measured-6d-wrench.cpp
Go to the documentation of this file.
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 
19 
21 
22 namespace tsid {
23 namespace contacts {
24 
25 using namespace std;
26 using namespace math;
27 using namespace pinocchio;
28 
30  const std::string &frameName)
31  : MeasuredForceBase(name, robot), m_frame_name(frameName) {
32  assert(m_robot.model().existFrame(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 
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();
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 
64  m_fext = fext;
65 }
66 
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
tsid::robots::RobotWrapper::framePosition
SE3 framePosition(const Data &data, const Model::FrameIndex index) const
Definition: src/robots/robot-wrapper.cpp:216
tsid::contacts::Measured6Dwrench::m_computedTorques
Vector m_computedTorques
Definition: contacts/measured-6d-wrench.hpp:65
pinocchio::DataTpl
tsid::contacts::Measured6Dwrench::computeJointTorques
const Vector & computeJointTorques(Data &data) override
Definition: src/contacts/measured-6d-wrench.cpp:43
pinocchio::SE3
context::SE3 SE3
tsid::contacts::Measured6Dwrench::Vector6
math::Vector6 Vector6
Definition: contacts/measured-6d-wrench.hpp:32
setup.data
data
Definition: setup.in.py:48
demo_quadruped.robot
robot
Definition: demo_quadruped.py:51
tsid::contacts::MeasuredForceBase
Definition: measured-force-base.hpp:28
tsid::contacts::Measured6Dwrench::m_J_rotated
Matrix6x m_J_rotated
Definition: contacts/measured-6d-wrench.hpp:64
ModelTpl< context::Scalar, context::Options >::existFrame
bool existFrame(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
tsid::contacts::Measured6Dwrench::m_frame_id
Index m_frame_id
Definition: contacts/measured-6d-wrench.hpp:61
tsid::robots::RobotWrapper::model
const Model & model() const
Accessor to model.
Definition: src/robots/robot-wrapper.cpp:102
robot-wrapper.hpp
tsid::contacts::Measured6Dwrench::m_J
Matrix6x m_J
Definition: contacts/measured-6d-wrench.hpp:63
ModelTpl< context::Scalar, context::Options >::getFrameId
FrameIndex getFrameId(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
tsid::contacts::Measured6Dwrench::getMeasuredContactForce
const Vector6 & getMeasuredContactForce() const
Definition: src/contacts/measured-6d-wrench.cpp:67
tsid::robots::RobotWrapper::frameJacobianLocal
void frameJacobianLocal(Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const
Definition: src/robots/robot-wrapper.cpp:338
tsid::contacts::Measured6Dwrench::Measured6Dwrench
Measured6Dwrench(const std::string &name, RobotWrapper &robot, const std::string &frameName)
Definition: src/contacts/measured-6d-wrench.cpp:29
demo_quadruped.contacts
int contacts
Definition: demo_quadruped.py:98
measured-6d-wrench.hpp
tsid::contacts::Measured6Dwrench::setMeasuredContactForce
void setMeasuredContactForce(const Vector6 &fext)
Definition: src/contacts/measured-6d-wrench.cpp:63
setup.name
name
Definition: setup.in.py:179
tsid::math::Vector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: math/fwd.hpp:35
tsid::contacts::Measured6Dwrench::m_fext
Vector6 m_fext
Definition: contacts/measured-6d-wrench.hpp:62
tsid::contacts::Measured6Dwrench::useLocalFrame
void useLocalFrame(bool local_frame)
Specifies if the external force and jacobian is expressed in the local frame or the local world-orien...
Definition: src/contacts/measured-6d-wrench.cpp:71
tsid
Definition: bindings/python/constraint/constraint-bound.cpp:21
std
tsid::robots::RobotWrapper
Wrapper for a robot based on pinocchio.
Definition: robots/robot-wrapper.hpp:37
tsid::contacts::MeasuredForceBase::m_robot
RobotWrapper & m_robot
Reference on the robot model.
Definition: measured-force-base.hpp:54
tsid::contacts::Measured6Dwrench::m_local_frame
bool m_local_frame
Definition: contacts/measured-6d-wrench.hpp:66
test_Contact.frameName
string frameName
Definition: test_Contact.py:29
pinocchio


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:16