diff --git a/VirtualRobot/CMakeLists.txt b/VirtualRobot/CMakeLists.txt index f09afe8aab09f035f22154b49bfd182bd360abe8..294ae06f6bca216b531b667718d03ff3f66a0895 100644 --- a/VirtualRobot/CMakeLists.txt +++ b/VirtualRobot/CMakeLists.txt @@ -333,8 +333,9 @@ SET(SOURCES Nodes/RobotNodeRevolute.cpp Nodes/RobotNodeRevoluteFactory.cpp Nodes/Sensor.cpp + Nodes/HemisphereJoint/CachedMaths.cpp Nodes/HemisphereJoint/Expressions.cpp - Nodes/HemisphereJoint/Joint.cpp + Nodes/HemisphereJoint/Maths.cpp TimeOptimalTrajectory/Path.cpp TimeOptimalTrajectory/TimeOptimalTrajectory.cpp @@ -577,8 +578,9 @@ SET(INCLUDES Nodes/RobotNodeRevoluteFactory.h Nodes/Sensor.h Nodes/SensorFactory.h + Nodes/HemisphereJoint/CachedMaths.h Nodes/HemisphereJoint/Expressions.h - Nodes/HemisphereJoint/Joint.h + Nodes/HemisphereJoint/Maths.h TimeOptimalTrajectory/Path.h TimeOptimalTrajectory/TimeOptimalTrajectory.h diff --git a/VirtualRobot/IK/DifferentialIK.cpp b/VirtualRobot/IK/DifferentialIK.cpp index e12d649b7280bd1abf3d4f2dd0663f3255f0b3b6..a37240e9d055530f97bd888f008b17ea1b893fdd 100644 --- a/VirtualRobot/IK/DifferentialIK.cpp +++ b/VirtualRobot/IK/DifferentialIK.cpp @@ -454,27 +454,19 @@ namespace VirtualRobot VR_ASSERT(hemisphere->first.has_value() xor hemisphere->second.has_value()); - if (hemisphere->first) + if (hemisphere->isFirstHemisphereJointNode()) { // Nothing to do - everything is handled by second DoF. } else { - VR_ASSERT(hemisphere->second); + VR_ASSERT(hemisphere->isSecondHemisphereJointNode()); // Set Jacobian for both DoFs. + const RobotNodeHemisphere::SecondData& second = hemisphere->getSecondData(); + const hemisphere::Maths::Jacobian jacobian = second.getJacobian(); - RobotNodeHemispherePtr second = hemisphere; - RobotNodeHemisphere* first = hemisphere->second->first; - - RobotNodeHemisphere::JointMath& math = first->first->math; - - Eigen::Vector2f actuators(first->getJointValue(), second->getJointValue()); - math.update(actuators); - - hemisphere::Joint::Jacobian jacobian = math.joint.getJacobian(); - - tmpUpdateJacobianPosition.block<6, 2>(0, i-1) = jacobian.cast<float>(); + tmpUpdateJacobianPosition.block<6, 2>(0, i - 1) = jacobian.cast<float>(); } } } diff --git a/VirtualRobot/Nodes/HemisphereJoint/CachedMaths.cpp b/VirtualRobot/Nodes/HemisphereJoint/CachedMaths.cpp new file mode 100644 index 0000000000000000000000000000000000000000..e52ac985bb26927b5dfff6ee22e9d45a67a3f7b2 --- /dev/null +++ b/VirtualRobot/Nodes/HemisphereJoint/CachedMaths.cpp @@ -0,0 +1,15 @@ +#include "CachedMaths.h" + + +namespace VirtualRobot::hemisphere +{ + + void CachedMaths::update(const Eigen::Vector2f& actuators) + { + if (actuators != this->actuators) + { + maths.computeFkOfAngle(actuators.cast<double>()); + } + } + +} diff --git a/VirtualRobot/Nodes/HemisphereJoint/CachedMaths.h b/VirtualRobot/Nodes/HemisphereJoint/CachedMaths.h new file mode 100644 index 0000000000000000000000000000000000000000..9f2c139326e794a6763b99db25ccb1612e7eb0ee --- /dev/null +++ b/VirtualRobot/Nodes/HemisphereJoint/CachedMaths.h @@ -0,0 +1,34 @@ +#pragma once + +#include "Maths.h" + +#include <Eigen/Core> + + +namespace VirtualRobot::hemisphere +{ + + /** + * @brief Wrapper around `hemisphere::Joint` caching the results. + */ + class CachedMaths + { + public: + + /** + * @brief Recompute the maths if the given `actuators` differ from + * the stored `actuators`. + */ + void update(const Eigen::Vector2f& actuators); + + public: + + /// The actuator values that were used to compute the joint math. + Eigen::Vector2f actuators = Eigen::Vector2f::Constant(std::numeric_limits<float>::min()); + + /// The joint math. + hemisphere::Maths maths; + + }; + +} diff --git a/VirtualRobot/Nodes/HemisphereJoint/Joint.cpp b/VirtualRobot/Nodes/HemisphereJoint/Maths.cpp similarity index 82% rename from VirtualRobot/Nodes/HemisphereJoint/Joint.cpp rename to VirtualRobot/Nodes/HemisphereJoint/Maths.cpp index f80cddf9abbd63f9ee8fe28a44699164e54aa566..539cee4df8b8e72135ab357a7db52c3d60949b4c 100644 --- a/VirtualRobot/Nodes/HemisphereJoint/Joint.cpp +++ b/VirtualRobot/Nodes/HemisphereJoint/Maths.cpp @@ -1,4 +1,4 @@ -#include "Joint.h" +#include "Maths.h" #include <cmath> @@ -9,19 +9,19 @@ namespace VirtualRobot::hemisphere { - Joint::Joint() : - Joint(1, simox::math::deg_to_rad(25.)) + Maths::Maths() : + Maths(1, simox::math::deg_to_rad(25.)) { } - Joint::Joint(double lever, double theta0) + Maths::Maths(double lever, double theta0) { this->setConstants(lever, theta0); } - void Joint::setConstants(double lever, double theta0) + void Maths::setConstants(double lever, double theta0) { this->lever = lever; this->theta0 = theta0; @@ -32,25 +32,25 @@ namespace VirtualRobot::hemisphere } - void Joint::computeFkOfPosition(double p1, double p2) + void Maths::computeFkOfPosition(double p1, double p2) { expressions.compute(p1, p2, lever, theta0); } - void Joint::computeFkOfPosition(const ActuatorPosition& p12) + void Maths::computeFkOfPosition(const ActuatorPosition& p12) { computeFkOfPosition(p12(0), p12(1)); } - void Joint::computeFkOfAngle(const ActuatorAngle& alpha12) + void Maths::computeFkOfAngle(const ActuatorAngle& alpha12) { computeFkOfPosition(angleToPosition(alpha12)); } - Eigen::Vector3d Joint::getEndEffectorTranslation() const + Eigen::Vector3d Maths::getEndEffectorTranslation() const { return Eigen::Vector3d { expressions.ex, @@ -60,7 +60,7 @@ namespace VirtualRobot::hemisphere } - Eigen::Matrix3d Joint::getEndEffectorRotation() const + Eigen::Matrix3d Maths::getEndEffectorRotation() const { // r_wrist_to_base = np.array([[exx, eyx, ezx], [exy, eyy, ezy], [exz, eyz, ezz]]) Eigen::Matrix3d ori; @@ -71,15 +71,15 @@ namespace VirtualRobot::hemisphere } - Eigen::Matrix4d Joint::getEndEffectorTransform() const + Eigen::Matrix4d Maths::getEndEffectorTransform() const { return simox::math::pose(getEndEffectorTranslation(), getEndEffectorRotation()); } - Joint::Jacobian Joint::getJacobian() const + Maths::Jacobian Maths::getJacobian() const { - Joint::Jacobian jacobian; + Maths::Jacobian jacobian; jacobian << expressions.jx1, expressions.jx2, expressions.jy1, expressions.jy2, expressions.jz1, expressions.jz2, @@ -127,7 +127,7 @@ namespace VirtualRobot::hemisphere } - Joint::ActuatorPosition Joint::angleToPosition(const Joint::ActuatorAngle& alpha) const + Maths::ActuatorPosition Maths::angleToPosition(const Maths::ActuatorAngle& alpha) const { return lever * Eigen::sin((alpha + Eigen::Vector2d::Constant(theta0)).array()); } diff --git a/VirtualRobot/Nodes/HemisphereJoint/Joint.h b/VirtualRobot/Nodes/HemisphereJoint/Maths.h similarity index 94% rename from VirtualRobot/Nodes/HemisphereJoint/Joint.h rename to VirtualRobot/Nodes/HemisphereJoint/Maths.h index f22897dd29fca296e66cc61fadcab0cc73290a65..b4c5cfa4613b77f7273afb09732e88889df968fd 100644 --- a/VirtualRobot/Nodes/HemisphereJoint/Joint.h +++ b/VirtualRobot/Nodes/HemisphereJoint/Maths.h @@ -15,7 +15,7 @@ namespace VirtualRobot::hemisphere * math code that was generated from Python sympy expressions * using `python/hemisphere-joint-demo/hemisphere_joint_demo/sympy_to_code.py`. */ - class Joint + class Maths { public: @@ -25,8 +25,8 @@ namespace VirtualRobot::hemisphere public: - Joint(); - Joint(double lever, double theta0); + Maths(); + Maths(double lever, double theta0); void setConstants(double lever, double theta0); diff --git a/VirtualRobot/Nodes/RobotNodeHemisphere.cpp b/VirtualRobot/Nodes/RobotNodeHemisphere.cpp index 86a9fe6ffc6cf3bbc8500dec3697b744625b8099..5349a937bd248f6bba3370fc39c5aa2c60beddf4 100644 --- a/VirtualRobot/Nodes/RobotNodeHemisphere.cpp +++ b/VirtualRobot/Nodes/RobotNodeHemisphere.cpp @@ -109,16 +109,16 @@ namespace VirtualRobot void RobotNodeHemisphere::setXmlInfo(const XmlInfo& info) { - VR_ASSERT(second.has_value()); + VR_ASSERT(secondData.has_value()); switch (info.role) { case Role::FIRST: - first.emplace(First{}); - first->math.joint.setConstants(info.lever, info.theta0); + firstData.emplace(FirstData{}); + firstData->maths.maths.setConstants(info.lever, info.theta0); break; case Role::SECOND: - second.emplace(Second{}); + secondData.emplace(SecondData{}); break; } } @@ -128,17 +128,17 @@ namespace VirtualRobot SceneObjectPtr parent, const std::vector<SceneObjectPtr>& children) { - VR_ASSERT_MESSAGE(first.has_value() xor second.has_value(), std::stringstream() << first.has_value() << " / " << second.has_value()); + VR_ASSERT_MESSAGE(firstData.has_value() xor secondData.has_value(), std::stringstream() << firstData.has_value() << " / " << secondData.has_value()); // The second node needs to store a reference to the first node. - if (second) + if (secondData) { - VR_ASSERT_MESSAGE(not second->first, "Second must not be initialized yet."); + VR_ASSERT_MESSAGE(not secondData->first, "Second must not be initialized yet."); RobotNodeHemisphere* firstNode = dynamic_cast<RobotNodeHemisphere*>(parent.get()); RobotNodeHemisphere* secondNode = this; - if (not (firstNode and firstNode->first)) + if (not (firstNode and firstNode->firstData)) { std::stringstream ss; ss << "The parent of a hemisphere joint with role '" << RoleNames.to_name(Role::SECOND) << "' " @@ -147,11 +147,12 @@ namespace VirtualRobot } // Save pointer to firstNode - second->first = firstNode; + secondData->firstNode = firstNode; + secondData->secondNode = secondNode; // Set up robot node parameters. { - const hemisphere::Joint& joint = second->math().joint; + const hemisphere::Maths& joint = secondData->maths().maths; firstNode->jointLimitLo = joint.limitLo; secondNode->jointLimitLo = joint.limitLo; @@ -165,35 +166,26 @@ namespace VirtualRobot } - void RobotNodeHemisphere::JointMath::update(const Eigen::Vector2f& actuators) - { - if (actuators != this->actuators) - { - joint.computeFkOfAngle(actuators.cast<double>()); - } - } - - void RobotNodeHemisphere::updateTransformationMatrices( const Eigen::Matrix4f& parentPose) { - VR_ASSERT_MESSAGE(first.has_value() xor second.has_value(), std::stringstream() << first.has_value() << " / " << second.has_value()); + VR_ASSERT_MESSAGE(firstData.has_value() xor secondData.has_value(), std::stringstream() << firstData.has_value() << " / " << secondData.has_value()); - if (first) + if (firstData) { globalPose = parentPose * localTransformation; } - else if (second) + else if (secondData) { - VR_ASSERT_MESSAGE(second->first, "First node must be known to second node."); + VR_ASSERT_MESSAGE(secondData->first, "First node must be known to second node."); - JointMath& math = second->math(); - Eigen::Vector2f actuators(second->first->getJointValue(), this->getJointValue()); + hemisphere::CachedMaths& math = secondData->maths(); + Eigen::Vector2f actuators(secondData->firstNode->getJointValue(), this->getJointValue()); math.update(actuators); - Eigen::Vector3d translation = math.joint.getEndEffectorTranslation(); - const Eigen::Matrix3d rotation = math.joint.getEndEffectorRotation(); + Eigen::Vector3d translation = math.maths.getEndEffectorTranslation(); + const Eigen::Matrix3d rotation = math.maths.getEndEffectorRotation(); const Eigen::Matrix4d transform = simox::math::pose(translation, rotation); // Update Second @@ -202,12 +194,12 @@ namespace VirtualRobot Eigen::IOFormat iof(5, 0, " ", "\n", " [", "]"); std::cout << __FUNCTION__ << "() of second actuator with " - << "\n lever = " << math.joint.lever - << "\n theta0 = " << math.joint.theta0 - << "\n radius = " << math.joint.radius + << "\n lever = " << math.maths.lever + << "\n theta0 = " << math.maths.theta0 + << "\n radius = " << math.maths.radius << "\n joint value = " << jointValue << "\n actuator (angle) = \n" << actuators.transpose().format(iof) - << "\n actuator (pos) = \n" << math.joint.angleToPosition(actuators.cast<double>()).transpose().format(iof) + << "\n actuator (pos) = \n" << math.maths.angleToPosition(actuators.cast<double>()).transpose().format(iof) << "\n local transform = \n" << localTransformation.format(iof) << "\n joint transform = \n" << transform.format(iof) << std::endl; @@ -219,7 +211,7 @@ namespace VirtualRobot void RobotNodeHemisphere::print(bool printChildren, bool printDecoration) const { ReadLockPtr lock = getRobot()->getReadLock(); - VR_ASSERT_MESSAGE(first.has_value() xor second.has_value(), std::stringstream() << first.has_value() << " / " << second.has_value()); + VR_ASSERT_MESSAGE(firstData.has_value() xor secondData.has_value(), std::stringstream() << firstData.has_value() << " / " << secondData.has_value()); if (printDecoration) { @@ -228,14 +220,14 @@ namespace VirtualRobot RobotNode::print(false, false); - if (first) + if (firstData) { std::cout << "* Hemisphere joint first node"; } - else if (second) + else if (secondData) { std::cout << "* Hemisphere joint second node"; - std::cout << "* Transform: \n" << second->math().joint.getEndEffectorTransform() << std::endl; + std::cout << "* Transform: \n" << secondData->maths().maths.getEndEffectorTransform() << std::endl; } if (printDecoration) @@ -288,15 +280,15 @@ namespace VirtualRobot jointValueOffset, physics, colChecker, nodeType)); } - if (this->first) + if (this->firstData) { // We can just copy the math object. - cloned->first = first; + cloned->firstData = this->firstData; } - else if (this->second) + else if (this->secondData) { - cloned->second.emplace(Second{}); - // initialize() takes care of hooking up the second to the first. + cloned->secondData.emplace(SecondData{}); + // initialize() takes care of hooking up the second node to the first node. } return cloned; @@ -308,6 +300,27 @@ namespace VirtualRobot return true; } + bool RobotNodeHemisphere::isFirstHemisphereJointNode() const + { + return firstData.has_value(); + } + + bool RobotNodeHemisphere::isSecondHemisphereJointNode() const + { + return secondData.has_value(); + } + + const RobotNodeHemisphere::SecondData& RobotNodeHemisphere::getSecondData() const + { + VR_ASSERT(secondData.has_value()); + return secondData.value(); + } + + RobotNodeHemisphere::SecondData& RobotNodeHemisphere::getSecondData() + { + VR_ASSERT(secondData.has_value()); + return secondData.value(); + } void RobotNodeHemisphere::checkValidRobotNodeType() { @@ -318,20 +331,20 @@ namespace VirtualRobot std::string RobotNodeHemisphere::_toXML(const std::string& /*modelPath*/) { - VR_ASSERT_MESSAGE(first.has_value() xor second.has_value(), std::stringstream() << first.has_value() << " / " << second.has_value()); + VR_ASSERT_MESSAGE(firstData.has_value() xor secondData.has_value(), std::stringstream() << firstData.has_value() << " / " << secondData.has_value()); - if (first) + if (firstData) { // TODO return ""; } else { - JointMath& math = second->math(); + hemisphere::CachedMaths& math = secondData->maths(); std::stringstream ss; ss << "\t\t<Joint type='Hemisphere'>" << std::endl; - ss << "\t\t\t<hemisphere lever='" << math.joint.lever << "' theta0='" << math.joint.theta0 << "' />" << std::endl; + ss << "\t\t\t<hemisphere lever='" << math.maths.lever << "' theta0='" << math.maths.theta0 << "' />" << std::endl; ss << "\t\t\t<limits lo='" << jointLimitLo << "' hi='" << jointLimitHi << "' units='radian'/>" << std::endl; ss << "\t\t\t<MaxAcceleration value='" << maxAcceleration << "'/>" << std::endl; ss << "\t\t\t<MaxVelocity value='" << maxVelocity << "'/>" << std::endl; @@ -349,4 +362,28 @@ namespace VirtualRobot } } + hemisphere::CachedMaths& RobotNodeHemisphere::SecondData::maths() + { + return firstNode->firstData->maths; + } + + const hemisphere::CachedMaths& RobotNodeHemisphere::SecondData::maths() const + { + return firstNode->firstData->maths; + } + + hemisphere::Maths::Jacobian RobotNodeHemisphere::SecondData::getJacobian() const + { + VR_ASSERT(firstNode); + VR_ASSERT(secondNode); + + hemisphere::CachedMaths& maths = firstNode->firstData->maths; + + Eigen::Vector2f actuators(firstNode->getJointValue(), secondNode->getJointValue()); + maths.update(actuators); + + hemisphere::Maths::Jacobian jacobian = maths.maths.getJacobian(); + return jacobian; + } + } diff --git a/VirtualRobot/Nodes/RobotNodeHemisphere.h b/VirtualRobot/Nodes/RobotNodeHemisphere.h index 343a20b86d913cb5cea392912e44b5829aa50d25..c3cb17525f1e225c2f2b7bc70ffd4cdfb4ba40aa 100644 --- a/VirtualRobot/Nodes/RobotNodeHemisphere.h +++ b/VirtualRobot/Nodes/RobotNodeHemisphere.h @@ -21,10 +21,11 @@ */ #pragma once -#include "../VirtualRobot.h" +#include <VirtualRobot/VirtualRobot.h> -#include "RobotNode.h" -#include "HemisphereJoint/Joint.h" +#include <VirtualRobot/Nodes/RobotNode.h> +#include <VirtualRobot/Nodes/HemisphereJoint/CachedMaths.h> +#include <VirtualRobot/Nodes/HemisphereJoint/Maths.h> #include <Eigen/Core> @@ -38,17 +39,31 @@ namespace VirtualRobot using RobotNodeHemispherePtr = std::shared_ptr<class RobotNodeHemisphere>; + /** + * @brief A model of the 2 DoF wrist joint mechanism published in: + * + * C. Klas and T. Asfour, "A Compact, Lightweight and Singularity-Free + * Wrist Joint Mechanism for Humanoid Robots," 2022 IEEE/RSJ International + * Conference on Intelligent Robots and Systems (IROS), Kyoto, Japan, 2022, + * pp. 457-464, doi: 10.1109/IROS47612.2022.9981787. + * + * This joint mechanism represents 2 Degrees of Freedom (DoF). Therefore, + * it must be represented by two robot nodes in VirtualRobot. + */ class VIRTUAL_ROBOT_IMPORT_EXPORT RobotNodeHemisphere : public RobotNode { public: enum class Role { + /// The first DoF in the kinematic chain. FIRST, + /// The second DoF in the kinematic chain. SECOND, }; static Role RoleFromString(const std::string& string); + /// Information specified in the robot XML. struct XmlInfo { Role role; @@ -58,8 +73,31 @@ namespace VirtualRobot double lever = -1; }; + + /// Data held by the first joint. + struct FirstData + { + hemisphere::CachedMaths maths; + }; + + /// Data held by the second joint. + struct SecondData + { + /// The first actuator node. + RobotNodeHemisphere* firstNode = nullptr; + RobotNodeHemisphere* secondNode = nullptr; + + hemisphere::CachedMaths& maths(); + const hemisphere::CachedMaths& maths() const; + + hemisphere::Maths::Jacobian getJacobian() const; + }; + friend class RobotFactory; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -118,6 +156,15 @@ namespace VirtualRobot bool isHemisphereJoint() const override; + bool isFirstHemisphereJointNode() const; + bool isSecondHemisphereJointNode() const; + + /** + * @brief Get the data held by the second node. + * May only be called if `isFirstHemisphereJointNode()`; + */ + SecondData& getSecondData(); + const SecondData& getSecondData() const; protected: @@ -140,48 +187,18 @@ namespace VirtualRobot ) override; RobotNodePtr - _clone( - const RobotPtr newRobot, - const VisualizationNodePtr visualizationModel, - const CollisionModelPtr collisionModel, - CollisionCheckerPtr colChecker, - float scaling - ) override; + _clone(const RobotPtr newRobot, + const VisualizationNodePtr visualizationModel, + const CollisionModelPtr collisionModel, + CollisionCheckerPtr colChecker, + float scaling + ) override; - public: - - struct JointMath - { - /// The actuator values that were used to compute the joint math. - Eigen::Vector2f actuators = Eigen::Vector2f::Constant(std::numeric_limits<float>::min()); - /// The joint math. - hemisphere::Joint joint; - - void update(const Eigen::Vector2f& actuators); - }; + private: - struct First - { - JointMath math; - }; - std::optional<First> first; - - struct Second - { - /// The first actuator node. - RobotNodeHemisphere* first = nullptr; - - JointMath& math() - { - return first->first->math; - } - const JointMath& math() const - { - return first->first->math; - } - }; - std::optional<Second> second; + std::optional<FirstData> firstData; + std::optional<SecondData> secondData; }; diff --git a/VirtualRobot/examples/HemisphereJoint/main.cpp b/VirtualRobot/examples/HemisphereJoint/main.cpp index 46693a0c20edf8a282074eb70026189f9b75676d..73f38a97a5c1aa15fbd01bb68a30877d81f14322 100644 --- a/VirtualRobot/examples/HemisphereJoint/main.cpp +++ b/VirtualRobot/examples/HemisphereJoint/main.cpp @@ -6,20 +6,17 @@ #include <SimoxUtility/math/statistics/measures.h> #include <VirtualRobot/RuntimeEnvironment.h> -#include <VirtualRobot/Nodes/HemisphereJoint/Joint.h> +#include <VirtualRobot/Nodes/HemisphereJoint/Maths.h> using VirtualRobot::RuntimeEnvironment; -/** - * - */ int main(int argc, char* argv[]) { const Eigen::IOFormat iof(5, 0, " ", "\n", " [", "]", "", ""); - RuntimeEnvironment::setCaption("Convert .iv to .wrl files"); + RuntimeEnvironment::setCaption("Compute hemisphere joint mathematics"); RuntimeEnvironment::considerFlag( "verbose", "Enable verbose output."); @@ -67,7 +64,7 @@ int main(int argc, char* argv[]) { const time_point start = std::chrono::system_clock::now(); - VirtualRobot::hemisphere::Joint joint; + VirtualRobot::hemisphere::Maths joint; joint.computeFkOfPosition(a1, a2); const Eigen::Vector3d pos = joint.getEndEffectorTranslation(); @@ -109,7 +106,7 @@ int main(int argc, char* argv[]) a1 += offset; a2 += offset; - VirtualRobot::hemisphere::Joint joint; + VirtualRobot::hemisphere::Maths joint; joint.computeFkOfPosition(a1, a2); const Eigen::Vector3d pos = joint.getEndEffectorTranslation();