From ae0515e4c44b5b5025a5139c7f8c40de89c3de2e Mon Sep 17 00:00:00 2001 From: Fabian Reister <fabian.reister@kit.edu> Date: Thu, 4 Mar 2021 15:03:00 +0100 Subject: [PATCH] velocity & header interface change --- .../components/units/PlatformUnitObserver.cpp | 13 +- .../units/PlatformUnitSimulation.cpp | 48 ++- .../components/units/PlatformUnitSimulation.h | 7 +- ...onomicPlatformGlobalPositionController.cpp | 3 - .../units/RobotUnit/Units/PlatformSubUnit.cpp | 279 ++++++++++-------- .../units/RobotUnit/Units/PlatformSubUnit.h | 19 +- .../interface/units/PlatformUnitInterface.ice | 9 +- 7 files changed, 219 insertions(+), 159 deletions(-) diff --git a/source/RobotAPI/components/units/PlatformUnitObserver.cpp b/source/RobotAPI/components/units/PlatformUnitObserver.cpp index ebc1fd675..97faeee2f 100644 --- a/source/RobotAPI/components/units/PlatformUnitObserver.cpp +++ b/source/RobotAPI/components/units/PlatformUnitObserver.cpp @@ -86,14 +86,13 @@ namespace armarx // odometry pose is always zero in the beginning - set it so that it can be queried PoseStamped initialOdomPose; - initialOdomPose.header.frame = OdometryFrame; - initialOdomPose.header.agent = RobotFrame; - // FIXME(fabian.reister): set timestamp properly + initialOdomPose.header.parentFrame = OdometryFrame; + initialOdomPose.header.frame = platformNodeName; + initialOdomPose.header.agent = ""; initialOdomPose.header.timestampInMicroSeconds = armarx::TimeUtil::GetTime().toMicroSeconds(); initialOdomPose.pose = Eigen::Matrix4f::Identity(); - reportPlatformOdometryPose(initialOdomPose, Ice::emptyCurrent); } @@ -118,9 +117,9 @@ namespace armarx void PlatformUnitObserver::reportPlatformVelocity(const VelocityStamped& platfromVelocity, const Ice::Current& c) { - setDataField("platformVelocity", "velocityX", platfromVelocity.velocity.x()); - setDataField("platformVelocity", "velocityY", platfromVelocity.velocity.y()); - setDataField("platformVelocity", "velocityRotation", platfromVelocity.velocity(5)); + setDataField("platformVelocity", "velocityX", platfromVelocity.linearVelocity.x()); + setDataField("platformVelocity", "velocityY", platfromVelocity.linearVelocity.y()); + setDataField("platformVelocity", "velocityRotation", platfromVelocity.angularVelocity.z()); updateChannel("platformVelocity"); } diff --git a/source/RobotAPI/components/units/PlatformUnitSimulation.cpp b/source/RobotAPI/components/units/PlatformUnitSimulation.cpp index f917c29d0..a086d8476 100644 --- a/source/RobotAPI/components/units/PlatformUnitSimulation.cpp +++ b/source/RobotAPI/components/units/PlatformUnitSimulation.cpp @@ -67,9 +67,18 @@ namespace armarx void PlatformUnitSimulation::onStartPlatformUnit() { + usingProxy("RobotStateComponent"); + + robotStateComponent = getProxy<RobotStateComponentInterfacePrx>("RobotStateComponent"); + agentName = robotStateComponent->getRobotName(); + + // fails if children is empty + robotRootFrame = robotStateComponent->getRobotInfo()->children.front()->name; + PoseStamped currentPose; - // FIXME(fabian.reister): set frame and agent - // FIXME(fabian.reister): Take the timestamp from simulation + currentPose.header.parentFrame = GlobalFrame; + currentPose.header.frame = robotRootFrame; + currentPose.header.agent = agentName; currentPose.header.timestampInMicroSeconds = TimeUtil::GetTime().toMicroSeconds(); currentPose.pose = currentPlatformPose(); @@ -94,13 +103,6 @@ namespace armarx } } - void PlatformUnitSimulation::fillCommonPlatformFields(FrameHeader& header) - { - header.timestampInMicroSeconds = TimeUtil::GetTime().toMicroSeconds(); - header.frame = GlobalFrame; - header.agent = RobotFrame; - } - void PlatformUnitSimulation::simulationFunction() { // the time it took until this method was called again @@ -179,14 +181,28 @@ namespace armarx } } + // odom velocity is in local robot frame + FrameHeader odomVelocityHeader; + odomVelocityHeader.parentFrame = robotRootFrame; + odomVelocityHeader.frame = robotRootFrame; + odomVelocityHeader.agent = agentName; + odomVelocityHeader.timestampInMicroSeconds = TimeUtil::GetTime().toMicroSeconds();; + + // odom pose is in odom frame + FrameHeader odomPoseHeader; + odomPoseHeader.parentFrame = OdometryFrame; + odomPoseHeader.frame = robotRootFrame; + odomPoseHeader.agent = agentName; + odomPoseHeader.timestampInMicroSeconds = TimeUtil::GetTime().toMicroSeconds();; PoseStamped platformPose; - fillCommonPlatformFields(platformPose.header); + platformPose.header = odomPoseHeader; platformPose.pose = currentPlatformPose(); VelocityStamped platformVelocity; - fillCommonPlatformFields(platformVelocity.header); - platformVelocity.velocity << vel[0], vel[1], 0.F, 0.F, 0.F, vel[2]; + platformVelocity.header = odomVelocityHeader; + platformVelocity.linearVelocity << vel[0], vel[1], 0; + platformVelocity.angularVelocity << 0, 0, vel[2]; listenerPrx->reportPlatformPose(platformPose); listenerPrx->reportPlatformVelocity(platformVelocity); @@ -205,8 +221,14 @@ namespace armarx this->orientationalAccuracy = orientationalAccuracy; } + FrameHeader header; + header.timestampInMicroSeconds = TimeUtil::GetTime().toMicroSeconds(); + header.parentFrame = GlobalFrame; + header.frame = robotRootFrame; + header.agent = agentName; + PoseStamped targetPose; - fillCommonPlatformFields(targetPose.header); + targetPose.header = header; targetPose.pose = VirtualRobot::MathTools::posrpy2eigen4f(targetPositionX, targetPositionY, 0, 0, 0, targetRotation); listenerPrx->reportNewTargetPose(targetPose); diff --git a/source/RobotAPI/components/units/PlatformUnitSimulation.h b/source/RobotAPI/components/units/PlatformUnitSimulation.h index 504c4f2f1..51b7eb2f7 100644 --- a/source/RobotAPI/components/units/PlatformUnitSimulation.h +++ b/source/RobotAPI/components/units/PlatformUnitSimulation.h @@ -29,6 +29,7 @@ #include <ArmarXCore/core/services/tasks/PeriodicTask.h> #include <ArmarXCore/core/system/ImportExportComponent.h> #include <RobotAPI/libraries/core/PIDController.h> +#include <RobotAPI/interface/core/RobotState.h> #include <IceUtil/Time.h> @@ -136,7 +137,11 @@ namespace armarx private: Eigen::Matrix4f currentPlatformPose() const; - void fillCommonPlatformFields(FrameHeader& header); + + RobotStateComponentInterfacePrx robotStateComponent; + std::string agentName; + std::string robotRootFrame; + }; } diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.cpp index 4e305e90e..fd1522db9 100755 --- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.cpp +++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.cpp @@ -126,10 +126,7 @@ namespace armarx { // ..todo: check if norm is too large - // TODO(fabian.reister): add check: frame and agent have to be "Global" and "robot" - const float yaw = simox::math::mat4f_to_rpy(currentPose.pose).z(); - const Eigen::Affine3f pose(currentPose.pose); getWriterControlStruct().globalPosition << pose.translation().x(), pose.translation().y(); diff --git a/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.cpp b/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.cpp index ae198cc35..70555bd86 100755 --- a/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.cpp +++ b/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.cpp @@ -25,164 +25,183 @@ #include <Eigen/Geometry> #include <RobotAPI/interface/core/PoseBase.h> +#include <RobotAPI/libraries/core/FramedPose.h> -namespace armarx { +namespace armarx +{ + void armarx::PlatformSubUnit::update(const armarx::SensorAndControl& sc, const JointAndNJointControllers&) + { + if (!getProxy()) + { + //this unit is not initialized yet + ARMARX_IMPORTANT << deactivateSpam(1) << "not initialized yet - skipping this update"; + return; + } + if (!listenerPrx) + { + ARMARX_INFO << deactivateSpam(1) << "listener is not set - skipping this update"; + return; + } + const SensorValueBase* sensorValue = sc.sensors.at(platformSensorIndex).get(); + ARMARX_CHECK_EXPRESSION(sensorValue); + std::lock_guard<std::mutex> guard {dataMutex}; + + const auto timestamp = sc.sensorValuesTimestamp.toMicroSeconds();; + + // odom velocity is in local robot frame + FrameHeader odomVelocityHeader; + odomVelocityHeader.parentFrame = robotRootFrame; + odomVelocityHeader.frame = robotRootFrame; + odomVelocityHeader.agent = ""; + odomVelocityHeader.timestampInMicroSeconds = timestamp; + + // odom pose is in odom frame + FrameHeader odomPoseHeader; + odomPoseHeader.parentFrame = OdometryFrame; + odomPoseHeader.frame = robotRootFrame; + odomPoseHeader.agent = agentName; + odomPoseHeader.timestampInMicroSeconds = timestamp; + + // odom velocity is in local robot frame + FrameHeader globalPoseHeader; + globalPoseHeader.parentFrame = GlobalFrame; + globalPoseHeader.frame = robotRootFrame; + globalPoseHeader.agent = agentName; + globalPoseHeader.timestampInMicroSeconds = timestamp; + + //pos + { + ARMARX_CHECK_EXPRESSION(sensorValue->isA<SensorValueHolonomicPlatformRelativePosition>()); + const SensorValueHolonomicPlatformRelativePosition* s = sensorValue->asA<SensorValueHolonomicPlatformRelativePosition>(); + relX = s->relativePositionX; + relY = s->relativePositionY; + relR = s->relativePositionRotation; + + + // @@@ CHECK BELOW: + if (s->isA<SensorValueHolonomicPlatformAbsolutePosition>()) + { + const SensorValueHolonomicPlatformAbsolutePosition* sabs = s->asA<SensorValueHolonomicPlatformAbsolutePosition>(); + abs = positionCorrection * VirtualRobot::MathTools::posrpy2eigen4f(sabs->absolutePositionX, sabs->absolutePositionY, 0, 0, 0, sabs->absolutePositionRotation); + + PoseStamped currentPose; + currentPose.header = globalPoseHeader; + currentPose.pose = abs; + + listenerPrx->reportPlatformPose(currentPose); + globalPosCtrl->setGlobalPos(currentPose); + } + else + { + abs = positionCorrection * VirtualRobot::MathTools::posrpy2eigen4f(relX, relY, 0, 0, 0, relR); + } + + PoseStamped odomPose; + odomPose.header = odomPoseHeader; + odomPose.pose = VirtualRobot::MathTools::posrpy2eigen4f(relX, relY, 0, 0, 0, relR); + listenerPrx->reportPlatformOdometryPose(odomPose); + } + //vel + { + ARMARX_CHECK_EXPRESSION(sensorValue->isA<SensorValueHolonomicPlatformVelocity>()); + const SensorValueHolonomicPlatformVelocity* s = sensorValue->asA<SensorValueHolonomicPlatformVelocity>(); -void PlatformSubUnit::fillFields(armarx::FrameHeader& header, const armarx::SensorAndControl& sc){ - header.frame = ""; // FIXME(fabian.reister) - header.agent = ""; // FIXME(fabian.reister) - header.timestampInMicroSeconds = sc.sensorValuesTimestamp.toMicroSeconds(); -} + VelocityStamped odomVelocity; + odomVelocity.header = odomVelocityHeader; + odomVelocity.linearVelocity << s->velocityX, s->velocityY, 0; + odomVelocity.angularVelocity << 0, 0, s->velocityRotation; -void armarx::PlatformSubUnit::update(const armarx::SensorAndControl& sc, const JointAndNJointControllers&) -{ - if (!getProxy()) - { - //this unit is not initialized yet - ARMARX_IMPORTANT << deactivateSpam(1) << "not initialized yet - skipping this update"; - return; + listenerPrx->reportPlatformVelocity(odomVelocity); + } } - if (!listenerPrx) + + void armarx::PlatformSubUnit::move(Ice::Float vx, Ice::Float vy, Ice::Float vr, const Ice::Current&) { - ARMARX_INFO << deactivateSpam(1) << "listener is not set - skipping this update"; - return; + //holding the mutex here could deadlock + if (!pt->isControllerActive()) + { + pt->activateController(); + } + std::lock_guard<std::mutex> guard {dataMutex}; + pt->setVelocites( + std::clamp(vx, -maxVLin, maxVLin), + std::clamp(vy, -maxVLin, maxVLin), + std::clamp(vr, -maxVAng, maxVAng) + ); } - const SensorValueBase* sensorValue = sc.sensors.at(platformSensorIndex).get(); - ARMARX_CHECK_EXPRESSION(sensorValue); - std::lock_guard<std::mutex> guard {dataMutex}; - //pos - { - ARMARX_CHECK_EXPRESSION(sensorValue->isA<SensorValueHolonomicPlatformRelativePosition>()); - const SensorValueHolonomicPlatformRelativePosition* s = sensorValue->asA<SensorValueHolonomicPlatformRelativePosition>(); - relX = s->relativePositionX; - relY = s->relativePositionY; - relR = s->relativePositionRotation; - - // @@@ CHECK BELOW: - if (s->isA<SensorValueHolonomicPlatformAbsolutePosition>()) + void armarx::PlatformSubUnit::moveTo(Ice::Float rx, Ice::Float ry, Ice::Float rr, Ice::Float lac, Ice::Float rac, const Ice::Current&) + { + globalPosCtrl->setTarget(rx, ry, rr, lac, rac); + if (!globalPosCtrl->isControllerActive()) { - const SensorValueHolonomicPlatformAbsolutePosition* sabs = s->asA<SensorValueHolonomicPlatformAbsolutePosition>(); - abs = positionCorrection * VirtualRobot::MathTools::posrpy2eigen4f(sabs->absolutePositionX, sabs->absolutePositionY, 0, 0, 0, sabs->absolutePositionRotation); - - PoseStamped currentPose; - fillFields(currentPose.header, sc); - - currentPose.pose = abs; + globalPosCtrl->activateController(); + }; + } - listenerPrx->reportPlatformPose(currentPose); - globalPosCtrl->setGlobalPos(currentPose); - } - else + void armarx::PlatformSubUnit::moveRelative(Ice::Float rx, Ice::Float ry, Ice::Float rr, Ice::Float lac, Ice::Float rac, const Ice::Current&) + { + relativePosCtrl->setTarget(rx, ry, rr, lac, rac); + if (!relativePosCtrl->isControllerActive()) { - abs = positionCorrection * VirtualRobot::MathTools::posrpy2eigen4f(relX, relY, 0, 0, 0, relR); + relativePosCtrl->activateController(); } + //holding the mutex here could deadlock + // std::lock_guard<std::mutex> guard {dataMutex}; + ARMARX_INFO << "target orientation: " << rr; - PoseStamped odomPose; - // FIXME(fabian.reister): fill fields - odomPose.pose = VirtualRobot::MathTools::posrpy2eigen4f(relX, relY, 0, 0, 0, relR); - listenerPrx->reportPlatformOdometryPose(odomPose); } - //vel - { - ARMARX_CHECK_EXPRESSION(sensorValue->isA<SensorValueHolonomicPlatformVelocity>()); - const SensorValueHolonomicPlatformVelocity* s = sensorValue->asA<SensorValueHolonomicPlatformVelocity>(); - - VelocityStamped odomVelocity; - // FIXME(fabian.reister): fill fields - odomVelocity.velocity << s->velocityX, s->velocityY, 0, 0, 0, s->velocityRotation; - listenerPrx->reportPlatformVelocity(odomVelocity); + void armarx::PlatformSubUnit::setMaxVelocities(Ice::Float mxVLin, Ice::Float mxVAng, const Ice::Current&) + { + std::lock_guard<std::mutex> guard {dataMutex}; + maxVLin = std::abs(mxVLin); + maxVAng = std::abs(mxVAng); } -} -void armarx::PlatformSubUnit::move(Ice::Float vx, Ice::Float vy, Ice::Float vr, const Ice::Current&) -{ - //holding the mutex here could deadlock - if (!pt->isControllerActive()) + void armarx::PlatformSubUnit::setGlobalPose(armarx::PoseBasePtr globalPose, const Ice::Current&) { - pt->activateController(); + std::lock_guard<std::mutex> guard {dataMutex}; + PosePtr p = PosePtr::dynamicCast(globalPose); + positionCorrection = p->toEigen() * abs.inverse(); } - std::lock_guard<std::mutex> guard {dataMutex}; - pt->setVelocites( - std::clamp(vx, -maxVLin, maxVLin), - std::clamp(vy, -maxVLin, maxVLin), - std::clamp(vr, -maxVAng, maxVAng) - ); -} - -void armarx::PlatformSubUnit::moveTo(Ice::Float rx, Ice::Float ry, Ice::Float rr, Ice::Float lac, Ice::Float rac, const Ice::Current&) -{ - globalPosCtrl->setTarget(rx, ry, rr, lac, rac); - if (!globalPosCtrl->isControllerActive()) - { - globalPosCtrl->activateController(); - }; -} -void armarx::PlatformSubUnit::moveRelative(Ice::Float rx, Ice::Float ry, Ice::Float rr, Ice::Float lac, Ice::Float rac, const Ice::Current&) -{ - relativePosCtrl->setTarget(rx, ry, rr, lac, rac); - if (!relativePosCtrl->isControllerActive()) + armarx::PoseBasePtr armarx::PlatformSubUnit::getGlobalPose(const Ice::Current&) { - relativePosCtrl->activateController(); + std::lock_guard<std::mutex> guard {dataMutex}; + return new Pose {abs}; } - //holding the mutex here could deadlock - // std::lock_guard<std::mutex> guard {dataMutex}; - ARMARX_INFO << "target orientation: " << rr; - -} - -void armarx::PlatformSubUnit::setMaxVelocities(Ice::Float mxVLin, Ice::Float mxVAng, const Ice::Current&) -{ - std::lock_guard<std::mutex> guard {dataMutex}; - maxVLin = std::abs(mxVLin); - maxVAng = std::abs(mxVAng); -} - -void armarx::PlatformSubUnit::setGlobalPose(armarx::PoseBasePtr globalPose, const Ice::Current&) -{ - std::lock_guard<std::mutex> guard {dataMutex}; - PosePtr p = PosePtr::dynamicCast(globalPose); - positionCorrection = p->toEigen() * abs.inverse(); -} -armarx::PoseBasePtr armarx::PlatformSubUnit::getGlobalPose(const Ice::Current&) -{ - std::lock_guard<std::mutex> guard {dataMutex}; - return new Pose {abs}; -} - -void armarx::PlatformSubUnit::stopPlatform(const Ice::Current& c) -{ - move(0, 0, 0); -} + void armarx::PlatformSubUnit::stopPlatform(const Ice::Current& c) + { + move(0, 0, 0); + } -Eigen::Matrix4f armarx::PlatformSubUnit::getRelativePose() const -{ - Eigen::Matrix4f rp = VirtualRobot::MathTools::rpy2eigen4f(0, 0, relR); - rp(0, 3) = relX; - rp(1, 3) = relY; - return rp; -} + Eigen::Matrix4f armarx::PlatformSubUnit::getRelativePose() const + { + Eigen::Matrix4f rp = VirtualRobot::MathTools::rpy2eigen4f(0, 0, relR); + rp(0, 3) = relX; + rp(1, 3) = relY; + return rp; + } -void armarx::PlatformSubUnit::reportPlatformPose(const PoseStamped& platformPose, const Ice::Current& c) -{ - globalPosCtrl->setGlobalPos(platformPose); -} + void armarx::PlatformSubUnit::reportPlatformPose(const PoseStamped& platformPose, const Ice::Current& c) + { + globalPosCtrl->setGlobalPos(platformPose); + } -void armarx::PlatformSubUnit::reportNewTargetPose(const PoseStamped& /*targetPlatformPose*/, const Ice::Current& c) -{ -} + void armarx::PlatformSubUnit::reportNewTargetPose(const PoseStamped& /*targetPlatformPose*/, const Ice::Current& c) + { + } -void armarx::PlatformSubUnit::reportPlatformVelocity(const VelocityStamped&, const Ice::Current& c) -{ -} + void armarx::PlatformSubUnit::reportPlatformVelocity(const VelocityStamped&, const Ice::Current& c) + { + } -void armarx::PlatformSubUnit::reportPlatformOdometryPose(const PoseStamped&, const Ice::Current&) -{ -} + void armarx::PlatformSubUnit::reportPlatformOdometryPose(const PoseStamped&, const Ice::Current&) + { + } } \ No newline at end of file diff --git a/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.h b/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.h index bba25a004..ae243d566 100755 --- a/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.h +++ b/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.h @@ -22,6 +22,7 @@ #pragma once +#include <RobotAPI/interface/core/RobotState.h> #include <mutex> #include <Eigen/Core> @@ -66,9 +67,19 @@ namespace armarx // PlatformUnit interface void onInitPlatformUnit() override { + // FIXME(fabian.reister): no hard coded name! usingTopic("PlatformState"); + usingProxy("RobotStateComponent"); + } + void onStartPlatformUnit() override + { + // FIXME(fabian.reister): no hard coded name! + robotStateComponent = getProxy<RobotStateComponentInterfacePrx>("RobotStateComponent"); + agentName = robotStateComponent->getRobotName(); + + // fails if children is empty + robotRootFrame = robotStateComponent->getRobotInfo()->children.front()->name; } - void onStartPlatformUnit() override {} void onExitPlatformUnit() override {} void stopPlatform(const Ice::Current& c = Ice::emptyCurrent) override; @@ -92,7 +103,11 @@ namespace armarx Eigen::Matrix4f positionCorrection = Eigen::Matrix4f::Identity(); - void fillFields(armarx::FrameHeader& header, const armarx::SensorAndControl& sc); + private: + RobotStateComponentInterfacePrx robotStateComponent; + std::string agentName; + std::string robotRootFrame; + }; } diff --git a/source/RobotAPI/interface/units/PlatformUnitInterface.ice b/source/RobotAPI/interface/units/PlatformUnitInterface.ice index 1b756cc71..33933b397 100644 --- a/source/RobotAPI/interface/units/PlatformUnitInterface.ice +++ b/source/RobotAPI/interface/units/PlatformUnitInterface.ice @@ -76,8 +76,10 @@ module armarx struct FrameHeader { - string frame; // source frame - string agent; // child frame + string parentFrame; + string frame; + + string agent; long timestampInMicroSeconds = 0; } @@ -94,7 +96,8 @@ module armarx /** * Linear (x,y,z) and angular (roll, pitch, yaw) velocities */ - Eigen::Vector6f velocity; // [mm, rad] + Eigen::Vector3f linearVelocity; // [mm/s] + Eigen::Vector3f angularVelocity; // [rad/s] } -- GitLab