ForceTorqueUtility.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T),
5  * Karlsruhe Institute of Technology (KIT), all rights reserved.
6  *
7  * ArmarX is free software; you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License version 2 as
9  * published by the Free Software Foundation.
10  *
11  * ArmarX is distributed in the hope that it will be useful, but
12  * WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with this program. If not, see <http://www.gnu.org/licenses/>.
18  *
19  * @author Simon Ottenhaus (simon dot ottenhaus at kit dot edu)
20  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
21  * GNU General Public License
22  */
23 
24 #include "ForceTorqueUtility.h"
25 
28 
30 {
31  ForceTorqueUtility::ForceTorqueUtility(const ForceTorqueUnitObserverInterfacePrx& forceTorqueObserver, const std::string& FTDatefieldName)
32  {
33  forceDf = DatafieldRefPtr::dynamicCast(forceTorqueObserver->getForceDatafield(FTDatefieldName));
34  torqueDf = DatafieldRefPtr::dynamicCast(forceTorqueObserver->getTorqueDatafield(FTDatefieldName));
35  calibrate();
36  }
37 
38  Eigen::Vector3f ForceTorqueUtility::getForce()
39  {
40  return forceDf->getDataField()->get<FramedDirection>()->toEigen() - initialForce;
41  }
42 
44  {
45  const auto force = forceDf->getDataField()->get<FramedDirection>();
46 
47  return FramedDirection(force->toEigen() - initialForce, force->getFrame(), force->agent);
48  }
49 
51  {
52  return torqueDf->getDataField()->get<FramedDirection>()->toEigen() - initialTorque;
53  }
54 
56  {
57  auto force = getForce();
58  auto torque = getTorque();
59  Eigen::Vector6f forceTorque;
60  forceTorque << force, torque;
61  return forceTorque;
62  }
63 
65  {
66  initialForce = forceDf->getDataField()->get<FramedDirection>()->toEigen();
67  initialTorque = torqueDf->getDataField()->get<FramedDirection>()->toEigen();
68  }
69 }
armarx::control::common::ft::ForceTorqueUtility::getForce
Eigen::Vector3f getForce()
Definition: ForceTorqueUtility.cpp:38
armarx::viz::toEigen
Eigen::Matrix4f toEigen(data::GlobalPose const &pose)
Definition: Interaction.h:46
armarx::control::common::ft
This file is part of ArmarX.
Definition: aron_conversions.cpp:29
armarx::control::common::ft::ForceTorqueUtility::getForceTorque
Eigen::Vector6f getForceTorque()
Definition: ForceTorqueUtility.cpp:55
ForceTorqueUtility.h
armarx::control::common::ft::ForceTorqueUtility::torqueDf
DatafieldRefPtr torqueDf
Definition: ForceTorqueUtility.h:53
armarx::control::common::ft::ForceTorqueUtility::getFramedForce
FramedDirection getFramedForce()
Definition: ForceTorqueUtility.cpp:43
DatafieldRef.h
FramedPose.h
armarx::control::common::ft::ForceTorqueUtility::calibrate
void calibrate()
Definition: ForceTorqueUtility.cpp:64
armarx::control::common::ft::ForceTorqueUtility::ForceTorqueUtility
ForceTorqueUtility(const ForceTorqueUnitObserverInterfacePrx &forceTorqueObserver, const std::string &FTDatefieldName)
Definition: ForceTorqueUtility.cpp:31
armarx::FramedDirection
FramedDirection is a 3 dimensional direction vector with a reference frame. The reference frame can b...
Definition: FramedPose.h:83
armarx::VariantType::FramedDirection
const VariantTypeId FramedDirection
Definition: FramedPose.h:38
armarx::control::common::ft::ForceTorqueUtility::initialForce
Eigen::Vector3f initialForce
Definition: ForceTorqueUtility.h:54
Eigen::Matrix< float, 6, 1 >
armarx::control::common::ft::ForceTorqueUtility::initialTorque
Eigen::Vector3f initialTorque
Definition: ForceTorqueUtility.h:55
armarx::control::common::ft::ForceTorqueUtility::forceDf
DatafieldRefPtr forceDf
Definition: ForceTorqueUtility.h:52
armarx::control::common::ft::ForceTorqueUtility::getTorque
Eigen::Vector3f getTorque()
Definition: ForceTorqueUtility.cpp:50