tsid  1.8.0
Efficient Task Space Inverse Dynamics for Multi-body Systems based on Pinocchio
measured-6d-wrench.hpp
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 
18 #ifndef __invdyn_measured_6d_wrench_hpp__
19 #define __invdyn_measured_6d_wrench_hpp__
20 
21 #include <pinocchio/multibody/data.hpp>
22 
24 
25 namespace tsid {
26 namespace contacts {
28  public:
29  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
30 
31  typedef math::Index Index;
36 
37  Measured6Dwrench(const std::string &name, RobotWrapper &robot,
38  const std::string &frameName);
39 
40  const Vector &computeJointTorques(Data &data) override;
41 
46  void setMeasuredContactForce(const Vector6 &fext);
47 
48  const Vector6 &getMeasuredContactForce() const;
49 
57  void useLocalFrame(bool local_frame);
58 
59  protected:
60  std::string m_frame_name;
67 };
68 } // namespace contacts
69 } // namespace tsid
70 
71 #endif // ifndef __invdyn_measured_6d_wrench_hpp__
Definition: measured-6d-wrench.hpp:27
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index Index
Definition: measured-6d-wrench.hpp:31
math::Vector6 Vector6
Definition: measured-6d-wrench.hpp:32
void useLocalFrame(bool local_frame)
Specifies if the external force and jacobian is expressed in the local frame or the local world-orien...
Definition: measured-6d-wrench.cpp:71
Matrix6x m_J_rotated
Definition: measured-6d-wrench.hpp:64
bool m_local_frame
Definition: measured-6d-wrench.hpp:66
const Vector6 & getMeasuredContactForce() const
Definition: measured-6d-wrench.cpp:67
pinocchio::Data::Matrix6x Matrix6x
Definition: measured-6d-wrench.hpp:35
pinocchio::Data Data
Definition: measured-6d-wrench.hpp:34
Vector m_computedTorques
Definition: measured-6d-wrench.hpp:65
void setMeasuredContactForce(const Vector6 &fext)
Definition: measured-6d-wrench.cpp:63
Matrix6x m_J
Definition: measured-6d-wrench.hpp:63
Index m_frame_id
Definition: measured-6d-wrench.hpp:61
Vector6 m_fext
Definition: measured-6d-wrench.hpp:62
std::string m_frame_name
Definition: measured-6d-wrench.hpp:60
const Vector & computeJointTorques(Data &data) override
Definition: measured-6d-wrench.cpp:43
Measured6Dwrench(const std::string &name, RobotWrapper &robot, const std::string &frameName)
Definition: measured-6d-wrench.cpp:29
robots::RobotWrapper RobotWrapper
Definition: measured-6d-wrench.hpp:33
Definition: measured-force-base.hpp:28
const std::string & name() const
Definition: measured-force-base.cpp:26
Wrapper for a robot based on pinocchio.
Definition: robot-wrapper.hpp:37
pinocchio::Data Data
Definition: inverse-dynamics-formulation-acc-force.cpp:30
pinocchio::Data::Matrix6x Matrix6x
Definition: measured-3d-force.cpp:29
std::size_t Index
Definition: fwd.hpp:53
Eigen::Matrix< Scalar, 6, 1 > Vector6
Definition: fwd.hpp:41
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: fwd.hpp:35
Definition: constraint-bound.hpp:25