Skip to content
Snippets Groups Projects
Forked from Florian Leander Singer / RobotAPI
6766 commits behind the upstream repository.
RobotStateComponent.cpp 14.99 KiB
/*
 * This file is part of ArmarX.
 *
 * Copyright (C) 2012-2016, 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    RobotStateComponent::
 * @author     ( at kit dot edu)
 * @date
 * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
 *             GNU General Public License
 */

#include "RobotStateComponent.h"
#include <boost/foreach.hpp>
#include <VirtualRobot/XML/RobotIO.h>
#include <VirtualRobot/Nodes/RobotNode.h>
#include <VirtualRobot/RobotNodeSet.h>
#include <boost/format.hpp>
#include <boost/foreach.hpp>
#include <ArmarXCore/core/system/ArmarXDataPath.h>
#include <ArmarXCore/core/ArmarXManager.h>
#include <ArmarXCore/core/ArmarXObjectScheduler.h>
#include <ArmarXCore/core/application/Application.h>

using namespace std;
using namespace VirtualRobot;
using namespace Eigen;
using namespace Ice;
using namespace boost;


namespace armarx
{
    RobotStateComponent::~RobotStateComponent()
    {
        try
        {
            if (_synchronizedPrx)
            {
                _synchronizedPrx->unref();
            }
        }
        catch (...)
        {}
    }


    void RobotStateComponent::onInitComponent()
    {

        historyLength = getProperty<int>("HistoryLength").getValue();
        history.clear();


        relativeRobotFile = getProperty<std::string>("RobotFileName").getValue();

        if (!ArmarXDataPath::getAbsolutePath(relativeRobotFile, robotFile))
        {
            throw UserException("Could not find robot file " + robotFile);
        }

        this->_synchronized = VirtualRobot::RobotIO::loadRobot(robotFile, VirtualRobot::RobotIO::eStructure);
        _synchronized->setName(getProperty<std::string>("AgentName").getValue());

        robotModelScaling = getProperty<float>("RobotModelScaling").getValue();
        ARMARX_INFO << "scale factor: " << robotModelScaling;
        if (robotModelScaling != 1.0f)
        {
            ARMARX_INFO << "Scaling robot model with scale factor " << robotModelScaling;
            _synchronized = _synchronized->clone(_synchronized->getName(), _synchronized->getCollisionChecker(), robotModelScaling);
        }

        if (this->_synchronized)
        {
            ARMARX_VERBOSE << "Loaded robot from file " << robotFile << ". Robot name: " << this->_synchronized->getName();
        }
        else
        {
            ARMARX_VERBOSE << "Failed loading robot from file " << robotFile;
        }

        robotNodeSetName = getProperty<std::string>("RobotNodeSetName").getValue();


        if (robotNodeSetName == "")
        {
            throw UserException("RobotNodeSet not defined");
        }

        VirtualRobot::RobotNodeSetPtr rns =  this->_synchronized->getRobotNodeSet(robotNodeSetName);

        if (!rns)
        {
            throw UserException("RobotNodeSet not defined");
        }

        vector<RobotNodePtr> nodes = rns->getAllRobotNodes();

        ARMARX_VERBOSE << "Using RobotNodeSet " << robotNodeSetName << " with " << nodes.size() << " robot nodes.";
        BOOST_FOREACH(RobotNodePtr node, nodes)
        {
            ARMARX_VERBOSE << "Node: " << node->getName() << endl;
        }
        usingTopic(robotNodeSetName + "State");


        /*VirtualRobot::RobotNodeSetPtr pns = this->_synchronized->getRobotNodeSet("Platform");
        if (pns)
        {
            usingTopic("PlatformState");
            vector<RobotNodePtr> nodes = pns->getAllRobotNodes();

            ARMARX_VERBOSE << "Using RobotNodeSet Platform with " << nodes.size() << " robot nodes.";
            BOOST_FOREACH(RobotNodePtr node, nodes)
            {
                ARMARX_VERBOSE << "Node: " << node->getName() << endl;
            }
        }*/
        _sharedRobotServant =  new SharedRobotServant(this->_synchronized);
        _sharedRobotServant->ref();
    }


    void RobotStateComponent::onConnectComponent()
    {

        this->_synchronizedPrx = SharedRobotInterfacePrx::uncheckedCast(getObjectAdapter()->addWithUUID(_sharedRobotServant));
        ARMARX_INFO << "Started RobotStateComponent" << flush;
        if (robotStateObs)
        {
            robotStateObs->setRobot(_synchronized);
        }
    }

    void RobotStateComponent::onDisconnectComponent()
    {
    }


    SharedRobotInterfacePrx RobotStateComponent::getSynchronizedRobot(const Current& current) const
    {
        if (!this->_synchronizedPrx)
        {
            throw NotInitializedException("Shared Robot is NULL", "getSynchronizedRobot");
        }

        return this->_synchronizedPrx;
    }


    SharedRobotInterfacePrx RobotStateComponent::getRobotSnapshot(const string& time, const Current& current)
    {
        if (!_synchronized)
        {
            throw NotInitializedException("Shared Robot is NULL", "getRobotSnapshot");
        }

        auto clone = this->_synchronized->clone(_synchronized->getName());

        SharedRobotServantPtr p = new SharedRobotServant(clone);
        p->setTimestamp(IceUtil::Time::microSecondsDouble(_sharedRobotServant->getTimestamp()->timestamp));
        auto result = getObjectAdapter()->addWithUUID(p);
        // virtal robot clone is buggy -> set global pose here
        p->setGlobalPose(new Pose(_synchronized->getGlobalPose()));
        return SharedRobotInterfacePrx::uncheckedCast(result);
    }

    SharedRobotInterfacePrx RobotStateComponent::getRobotSnapshotAtTimestamp(double time, const Current& current)
    {
        if (!_synchronized)
        {
            throw NotInitializedException("Shared Robot is NULL", "getRobotSnapshot");
        }

        VirtualRobot::RobotPtr clone = this->_synchronized->clone(_synchronized->getName());
        RobotStateConfig config;
        if (!interpolate(time, config))
        {
            ARMARX_WARNING << "Could not find or interpolate a robot state for time " << IceUtil::Time::microSeconds(time).toDateTime();
            return NULL;
        }

        clone->setJointValues(config.jointMap);
        clone->setGlobalPose(FramedPosePtr::dynamicCast(config.globalPose)->toEigen());
        SharedRobotServantPtr p = new SharedRobotServant(clone);
        p->setTimestamp(IceUtil::Time::microSecondsDouble(time));
        auto result = getObjectAdapter()->addWithUUID(p);
        // virtal robot clone is buggy -> set global pose here
        p->setGlobalPose(new Pose(_synchronized->getGlobalPose()));


        return SharedRobotInterfacePrx::uncheckedCast(result);
    }


    NameValueMap RobotStateComponent::getJointConfigAtTimestamp(double timestamp, const Current&) const
    {
        RobotStateConfig config;
        if (!interpolate(timestamp, config))
        {
            ARMARX_WARNING << "Could not find or interpolate a robot state for time " << IceUtil::Time::microSeconds(timestamp).toDateTime();
            return NameValueMap();
        }
        return config.jointMap;
    }


    RobotStateConfig RobotStateComponent::getRobotStateAtTimestamp(double timestamp, const Current&) const
    {
        RobotStateConfig config;
        if (!interpolate(timestamp, config))
        {
            ARMARX_WARNING << "Could not find or interpolate a robot state for time " << IceUtil::Time::microSeconds(timestamp).toDateTime();
            return RobotStateConfig();
        }
        return config;
    }

    bool RobotStateComponent::interpolate(double time, RobotStateConfig& config) const
    {
        boost::shared_lock<SharedMutex> lock(historyMutex);
        auto it = history.lower_bound(time);
        if (history.size() == 0)
        {
            return false;
        }
        if (time > history.rbegin()->first)
        {
            config = history.rbegin()->second;
        }
        else if (it == history.end())
        {
            return false;
        }
        else
        {
            config = it->second;
            if (it->first == time)
            {
                //                ARMARX_INFO_S << "No Interpolation needed: " << time;
            }
            else
            {
                // interpolate
                auto prevIt = std::prev(it);
                if (prevIt != history.end())
                {
                    long deltaT = it->first - prevIt->first;
                    double influenceNext = 1.0f - (double)(it->first - time) / deltaT;
                    double influencePrev = 1.0f - (double)(time - prevIt->first) / deltaT;
                    //                    ARMARX_INFO_S << "Interpolating: " << time << " prev: " << time - prevIt->first << " next: " << it->first - time << VAROUT(influenceNext) << VAROUT(influencePrev) << " sum: " << (influenceNext + influencePrev);
                    auto jointIt = prevIt->second.jointMap.begin();
                    for (auto & joint : config.jointMap)
                    {
                        joint.second = joint.second * influenceNext + jointIt->second * influencePrev;
                        jointIt++;
                    }
                    config.timestamp = time;
                    ARMARX_CHECK_EXPRESSION(it->second.globalPose);
                    ARMARX_CHECK_EXPRESSION(prevIt->second.globalPose);
                    Eigen::Matrix4f globalPoseNext = FramedPosePtr::dynamicCast(it->second.globalPose)->toEigen();
                    Eigen::Matrix4f globalPosePref = FramedPosePtr::dynamicCast(prevIt->second.globalPose)->toEigen();
                    Eigen::Quaternionf rotNext(globalPoseNext.block<3, 3>(0, 0));
                    Eigen::Quaternionf rotPrev(globalPosePref.block<3, 3>(0, 0));
                    Eigen::Quaternionf rotNew = rotPrev.slerp(influenceNext, rotNext);
                    Eigen::Matrix4f globalPose;
                    globalPose.block<3, 3>(0, 0) = rotNew.toRotationMatrix();
                    globalPose.block<3, 1>(0, 3) = globalPoseNext.block<3, 1>(0, 3) * influenceNext +
                                                   globalPosePref.block<3, 1>(0, 3) * influencePrev;

                }
            }
        }
        return true;
    }

    void RobotStateComponent::reportJointAngles(const NameValueMap& jointAngles, Ice::Long timestamp, bool aValueChanged, const Current& c)
    {
        //        IceUtil::Time start = IceUtil::Time::now();
        if (timestamp <= 0)
        {
            timestamp = IceUtil::Time::now().toMicroSeconds();
        }
        if (aValueChanged)
        {
            {
                WriteLockPtr lock = _synchronized->getWriteLock();

                std::vector<float> jv;
                std::vector< RobotNodePtr > nodes;
                BOOST_FOREACH(NameValueMap::value_type namedAngle, jointAngles)
                {
                    RobotNodePtr node = this->_synchronized->getRobotNode(namedAngle.first);
                    nodes.push_back(node);
                    jv.push_back(namedAngle.second);
                }
                _synchronized->setJointValues(nodes, jv);
            }

            if (robotStateObs)
            {
                robotStateObs->updatePoses();
            }
        }
        auto time = IceUtil::Time::microSeconds(timestamp);
        if (_sharedRobotServant)
        {
            _sharedRobotServant->setTimestamp(time);
        }
        boost::unique_lock<SharedMutex> lock(historyMutex);
        history.insert(history.end(), std::make_pair(time.toMicroSecondsDouble(), RobotStateConfig {time.toMicroSecondsDouble(),
                       new FramedPose(_synchronized->getGlobalPose(), GlobalFrame, ""),
                       jointAngles
                                                                                                   }));

        if (history.size() > historyLength)
        {
            history.erase(history.begin());
        }
        //        ARMARX_VERBOSE << deactivateSpam(2) << "my duration: " << (IceUtil::Time::now() - start).toMicroSecondsDouble() << " ms";


    }

    std::string RobotStateComponent::getRobotFilename(const Ice::Current&) const
    {
        return relativeRobotFile;
    }

    float RobotStateComponent::getScaling(const Ice::Current&) const
    {
        return robotModelScaling;
    }

    std::vector<string> RobotStateComponent::getArmarXPackages(const Current&) const
    {
        std::vector<string> result;
        auto packages = armarx::Application::GetProjectDependencies();
        packages.push_back(Application::GetProjectName());

        for (const std::string & projectName : packages)
        {
            if (projectName.empty())
            {
                continue;
            }

            result.push_back(projectName);
        }

        return result;
    }

    void RobotStateComponent::reportControlModeChanged(const NameControlModeMap& jointModes, Ice::Long timestamp, bool aValueChanged, const Current& c) {}
    void RobotStateComponent::reportJointVelocities(const NameValueMap& jointVelocities, Ice::Long timestamp, bool aValueChanged, const Current& c)
    {
        if (robotStateObs)
        {
            robotStateObs->updateNodeVelocities(jointVelocities);
        }
    }
    void RobotStateComponent::reportJointTorques(const NameValueMap& jointTorques, Ice::Long timestamp, bool aValueChanged, const Current& c) {}

    void RobotStateComponent::reportJointAccelerations(const NameValueMap& jointAccelerations, Ice::Long timestamp, bool aValueChanged, const Current& c)
    {

    }
    void RobotStateComponent::reportJointCurrents(const NameValueMap& jointCurrents, Ice::Long timestamp, bool aValueChanged, const Current& c) {}
    void RobotStateComponent::reportJointMotorTemperatures(const NameValueMap& jointMotorTemperatures, Ice::Long timestamp, bool aValueChanged, const Current& c) {}
    void RobotStateComponent::reportJointStatuses(const NameStatusMap& jointStatuses, Ice::Long timestamp, bool aValueChanged, const Current& c) {}

    PropertyDefinitionsPtr RobotStateComponent::createPropertyDefinitions()
    {
        return PropertyDefinitionsPtr(new RobotStatePropertyDefinitions(
                                          getConfigIdentifier()));
    }

    void RobotStateComponent::setRobotStateObserver(RobotStateObserverPtr observer)
    {
        robotStateObs = observer;
    }

    string RobotStateComponent::getRobotName(const Current&) const
    {
        if (_synchronized)
        {
            return _synchronizedPrx->getName();
        }
        else
        {
            throw NotInitializedException("Robot Ptr is NULL", "getName");
        }

    }

    string RobotStateComponent::getRobotNodeSetName(const Current&) const
    {
        if (robotNodeSetName.empty())
        {
            throw NotInitializedException("RobotNodeSetName is empty", "getRobotNodeSetName");
        }
        return robotNodeSetName;
    }

}