Newer
Older
/*
* This file is part of ArmarX.
*
* Copyright (C) 2011-2017, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
*
* ArmarX is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License version 2 as
* published by the Free Software Foundation.
*
* ArmarX is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
* @package ArmarX
* @author Mirko Waechter( mirko.waechter at kit dot edu)
* @date 2019
* @copyright http://www.gnu.org/licenses/gpl-2.0.txt
* GNU General Public License
*/
#include "DynamicsHelper.h"
#include <VirtualRobot/Dynamics/Dynamics.h>
#include <VirtualRobot/RobotNodeSet.h>
#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
Mirko Wächter
committed
#include <ArmarXCore/observers/filters/rtfilters/RTFilterBase.h>
#include <RobotAPI/components/units/RobotUnit/RobotUnit.h>
namespace armarx
{
DynamicsHelper::DynamicsHelper(RobotUnit* robotUnit) : robotUnit(robotUnit)
Mirko Wächter
committed
ARMARX_CHECK_EXPRESSION(robotUnit);
}
void
DynamicsHelper::addRobotPart(VirtualRobot::RobotNodeSetPtr rnsJoints,
VirtualRobot::RobotNodeSetPtr rnsBodies,
rtfilters::RTFilterBasePtr velocityFilter,
rtfilters::RTFilterBasePtr accelerationFilter)
{
DynamicsData data(rnsJoints, rnsBodies);
for (size_t i = 0; i < rnsJoints->getSize(); i++)
{
auto selectedJoint = robotUnit->getSensorDevice(rnsJoints->getNode(i)->getName());
if (selectedJoint)
{
auto sensorValue = const_cast<SensorValue1DoFActuator*>(
selectedJoint->getSensorValue()->asA<SensorValue1DoFActuator>());
ARMARX_CHECK_EXPRESSION(sensorValue) << rnsJoints->getNode(i)->getName();
ARMARX_DEBUG << "will calculate inverse dynamics for robot node "
<< rnsJoints->getNode(i)->getName();
data.nodeSensorVec.push_back(std::make_pair(rnsJoints->getNode(i), sensorValue));
}
else
{
ARMARX_INFO << "Joint " << rnsJoints->getNode(i)->getName() << " not found";
data.nodeSensorVec.push_back(std::make_pair(rnsJoints->getNode(i), nullptr));
}
Mirko Wächter
committed
if (velocityFilter)
{
data.velocityFilter.push_back(velocityFilter->clone());
}
if (accelerationFilter)
{
data.accelerationFilter.push_back(accelerationFilter->clone());
}
}
dataMap.emplace(std::make_pair(rnsJoints, data));
}
void
DynamicsHelper::update(const IceUtil::Time& sensorValuesTimestamp,
const IceUtil::Time& timeSinceLastIteration)
{
for (auto& pair : dataMap)
{
// first get current state of the robot (position, velocity, acceleration)
auto& data = pair.second;
auto& dynamics = data.dynamics;
{
size_t i = 0;
for (auto& node : data.nodeSensorVec)
{
ARMARX_CHECK_EXPRESSION(node.second) << node.first->getName();
data.q(i) = node.second->position;
if (i < data.velocityFilter.size() && data.velocityFilter.at(i) &&
!std::isnan(node.second->velocity))
Mirko Wächter
committed
{
data.qDot(i) = data.velocityFilter.at(i)->update(sensorValuesTimestamp,
node.second->velocity);
Mirko Wächter
committed
}
else
{
data.qDot(i) = node.second->velocity;
}
if (i < data.accelerationFilter.size() && data.accelerationFilter.at(i) &&
!std::isnan(node.second->acceleration))
Mirko Wächter
committed
{
data.qDDot(i) = data.accelerationFilter.at(i)->update(
sensorValuesTimestamp, node.second->acceleration);
Mirko Wächter
committed
}
else
{
data.qDDot(i) = node.second->acceleration;
}
i++;
}
}
// calculate external torques (tau) applied to robot induced by dynamics
dynamics.getGravityMatrix(data.q, data.tauGravity);
dynamics.getInverseDynamics(data.q, data.qDot, data.qDDot, data.tau);
// update virtual sensor values
size_t i = 0;
for (auto& node : data.nodeSensorVec)
{
auto torque = data.tau(i);
auto gravityTorque = data.tauGravity(i);
if (node.second)
{
node.second->inverseDynamicsTorque = -torque;
node.second->gravityTorque = -gravityTorque;
node.second->inertiaTorque = -(torque - gravityTorque);
}
i++;
}
}
}
DynamicsHelper::DynamicsData::DynamicsData(VirtualRobot::RobotNodeSetPtr rnsJoints,
VirtualRobot::RobotNodeSetPtr rnsBodies) :
rnsJoints(rnsJoints), rnsBodies(rnsBodies), dynamics(rnsJoints, rnsBodies)
{
q = qDot = qDDot = tau = tauGravity = Eigen::VectorXd::Zero(rnsJoints->getSize());
}
} // namespace armarx