From 8c5e4c6fd0ff37990cb62a81cca145ccb226fa56 Mon Sep 17 00:00:00 2001 From: Fabian Reister <fabian.reister@kit.edu> Date: Wed, 31 Jan 2024 18:36:20 +0100 Subject: [PATCH] GraspTrajectory: json reader + const correctness --- .../GraspingUtility/GraspTrajectory.cpp | 193 ++++++++++++++---- .../GraspingUtility/GraspTrajectory.h | 121 ++++++----- 2 files changed, 219 insertions(+), 95 deletions(-) diff --git a/source/RobotAPI/libraries/GraspingUtility/GraspTrajectory.cpp b/source/RobotAPI/libraries/GraspingUtility/GraspTrajectory.cpp index 045026b0e..7ab4f089a 100644 --- a/source/RobotAPI/libraries/GraspingUtility/GraspTrajectory.cpp +++ b/source/RobotAPI/libraries/GraspingUtility/GraspTrajectory.cpp @@ -23,10 +23,16 @@ #include "GraspTrajectory.h" +#include <filesystem> +#include <fstream> #include <memory> +#include <optional> +#include <SimoxUtility/json/eigen_conversion.h> +#include <SimoxUtility/json/json.hpp> #include <VirtualRobot/math/Helpers.h> +#include "ArmarXCore/core/logging/Logging.h" #include <ArmarXCore/core/exceptions/Exception.h> #include <ArmarXCore/core/rapidxml/wrapper/RapidXmlReader.h> #include <ArmarXCore/core/rapidxml/wrapper/RapidXmlWriter.h> @@ -105,14 +111,25 @@ namespace armarx handValues[cell.getKey()] = cell.asFloat(); } + // does not work at the moment + const auto shapeNode = nav.selectSingleNode("shape"); + // ARMARX_IMPORTANT << VAROUT(shapeNode.isValid()); + + std::optional<std::string> shape; + if (shapeNode.isString()) + { + shape = nav.selectSingleNode("shape").asString(); + // ARMARX_IMPORTANT << "shape: " << shape.value(); + } + if (!traj) { - traj = std::make_shared<GraspTrajectory>(pose, handValues); + traj = std::make_shared<GraspTrajectory>(pose, handValues, shape); } else { - traj->addKeypoint(pose, handValues, dt); + traj->addKeypoint(pose, handValues, dt, shape); } } return traj; @@ -122,7 +139,49 @@ namespace armarx GraspTrajectory::ReadFromFile(const std::string& filename) { ARMARX_TRACE; - return ReadFromReader(RapidXmlReader::FromFile(filename)); + const auto ext = std::filesystem::path(filename).extension(); + if (ext == ".xml") + { + return ReadFromReader(RapidXmlReader::FromFile(filename)); + } + if (ext == ".json") + { + return ReadFromJSON(filename); + } + + ARMARX_WARNING << "Unknown extension `" << ext << "`!"; + return nullptr; + } + + // NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE(GraspTrajectory::Keypoint,tcpTarget,handJointsTarget,shape,dt ); + + + inline void + from_json(const nlohmann::json& j, GraspTrajectoryKeypoint& kp) + { + const std::optional<std::string> shape = + j.contains("shape") ? std::optional<std::string>(j.at("shape").get<std::string>()) + : std::nullopt; + + const std::map<std::string, float> targetHandValues = + j.contains("HandValues") ? j.at("HandValues").get<std::map<std::string, float>>() + : std::map<std::string, float>{}; + + kp = GraspTrajectoryKeypoint(j.at("Pose"), targetHandValues, shape); + } + + GraspTrajectoryPtr + GraspTrajectory::ReadFromJSON(const std::string& filename) + { + ARMARX_CHECK(std::filesystem::exists(filename)); + std::ifstream ifs(filename); + + const nlohmann::json j = nlohmann::json::parse(ifs); + + std::vector<GraspTrajectoryKeypoint> traj; + traj = j; + + return std::make_shared<GraspTrajectory>(traj); } GraspTrajectoryPtr @@ -133,22 +192,43 @@ namespace armarx } GraspTrajectory::GraspTrajectory(const Eigen::Matrix4f& tcpStart, - const armarx::NameValueMap& handJointsStart) + const armarx::NameValueMap& handJointsStart, + const std::optional<std::string>& shape) { ARMARX_TRACE; - KeypointPtr keypoint(new Keypoint(tcpStart, handJointsStart)); + KeypointPtr keypoint(new Keypoint(tcpStart, handJointsStart, shape)); keypointMap[0] = keypoints.size(); keypoints.push_back(keypoint); } + GraspTrajectory::GraspTrajectory(const std::vector<Keypoint>& keypointz) + { + if (keypointz.empty()) + { + return; + } + + // insert first keypoint + keypointMap[0] = keypoints.size(); + keypoints.push_back(std::make_shared<Keypoint>(keypointz.front())); + + // insert remaining keypoints + for (std::size_t i = 1; i < keypointz.size(); i++) + { + const auto& kp = keypointz.at(i); + addKeypoint(kp.tcpTarget, kp.handJointsTarget, kp.dt, kp.shape); + } + } + void GraspTrajectory::addKeypoint(const Eigen::Matrix4f& tcpTarget, const armarx::NameValueMap& handJointsTarget, - float dt) + float dt, + const std::optional<std::string>& shape) { ARMARX_TRACE; KeypointPtr prev = lastKeypoint(); - KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget)); + KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget, shape)); keypoint->updateVelocities(prev, dt); float t = getDuration() + dt; keypointMap[t] = keypoints.size(); @@ -162,11 +242,18 @@ namespace armarx return keypoints.size(); } + const std::vector<GraspTrajectory::KeypointPtr>& + GraspTrajectory::getAllKeypoints() const + { + return keypoints; + } + void GraspTrajectory::insertKeypoint(size_t index, const Eigen::Matrix4f& tcpTarget, const armarx::NameValueMap& handJointsTarget, - float dt) + float dt, + const std::optional<std::string>& shape) { ARMARX_TRACE; if (index <= 0 || index > keypoints.size()) @@ -174,7 +261,7 @@ namespace armarx throw LocalException("Index out of range" + std::to_string(index)); } KeypointPtr prev = keypoints.at(index - 1); - KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget)); + KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget, shape)); keypoint->updateVelocities(prev, dt); if (index < keypoints.size()) { @@ -208,7 +295,8 @@ namespace armarx GraspTrajectory::replaceKeypoint(size_t index, const Eigen::Matrix4f& tcpTarget, const armarx::NameValueMap& handJointsTarget, - float dt) + float dt, + const std::optional<std::string>& shape) { ARMARX_TRACE; if (index <= 0 || index >= keypoints.size()) @@ -216,7 +304,7 @@ namespace armarx throw LocalException("Index out of range" + std::to_string(index)); } KeypointPtr prev = keypoints.at(index - 1); - KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget)); + KeypointPtr keypoint(new Keypoint(tcpTarget, handJointsTarget, shape)); keypoint->updateVelocities(prev, dt); keypoints.at(index) = keypoint; updateKeypointMap(); @@ -236,29 +324,29 @@ namespace armarx updateKeypointMap(); } - GraspTrajectory::KeypointPtr& - GraspTrajectory::lastKeypoint() + const GraspTrajectory::KeypointPtr& + GraspTrajectory::lastKeypoint() const { ARMARX_TRACE; return keypoints.at(keypoints.size() - 1); } - GraspTrajectory::KeypointPtr& - GraspTrajectory::getKeypoint(int i) + const GraspTrajectory::KeypointPtr& + GraspTrajectory::getKeypoint(int i) const { ARMARX_TRACE; return keypoints.at(i); } Eigen::Matrix4f - GraspTrajectory::getStartPose() + GraspTrajectory::getStartPose() const { ARMARX_TRACE; return getKeypoint(0)->getTargetPose(); } void - GraspTrajectory::getIndex(float t, int& i1, int& i2, float& f) + GraspTrajectory::getIndex(float t, int& i1, int& i2, float& f) const { ARMARX_TRACE; if (t <= 0) @@ -284,7 +372,7 @@ namespace armarx } Eigen::Vector3f - GraspTrajectory::GetPosition(float t) + GraspTrajectory::GetPosition(float t) const { ARMARX_TRACE; int i1, i2; @@ -295,7 +383,7 @@ namespace armarx } Eigen::Matrix3f - GraspTrajectory::GetOrientation(float t) + GraspTrajectory::GetOrientation(float t) const { ARMARX_TRACE; int i1, i2; @@ -312,14 +400,14 @@ namespace armarx } Eigen::Matrix4f - GraspTrajectory::GetPose(float t) + GraspTrajectory::GetPose(float t) const { ARMARX_TRACE; return ::math::Helpers::CreatePose(GetPosition(t), GetOrientation(t)); } std::vector<Eigen::Matrix4f> - GraspTrajectory::getAllKeypointPoses() + GraspTrajectory::getAllKeypointPoses() const { ARMARX_TRACE; std::vector<Eigen::Matrix4f> res; @@ -331,7 +419,7 @@ namespace armarx } std::vector<Eigen::Vector3f> - GraspTrajectory::getAllKeypointPositions() + GraspTrajectory::getAllKeypointPositions() const { ARMARX_TRACE; std::vector<Eigen::Vector3f> res; @@ -343,7 +431,7 @@ namespace armarx } std::vector<Eigen::Matrix3f> - GraspTrajectory::getAllKeypointOrientations() + GraspTrajectory::getAllKeypointOrientations() const { ARMARX_TRACE; std::vector<Eigen::Matrix3f> res; @@ -355,7 +443,7 @@ namespace armarx } armarx::NameValueMap - GraspTrajectory::GetHandValues(float t) + GraspTrajectory::GetHandValues(float t) const { ARMARX_TRACE; int i1, i2; @@ -373,8 +461,20 @@ namespace armarx return handTargetsMap; } + std::optional<std::string> + GraspTrajectory::GetShape(float t) const + { + ARMARX_TRACE; + int i1, i2; + float f; + getIndex(t, i1, i2, f); + + // i1 is the one before or at the timestamp t + return getKeypoint(i1)->shape; + } + Eigen::Vector3f - GraspTrajectory::GetPositionDerivative(float t) + GraspTrajectory::GetPositionDerivative(float t) const { ARMARX_TRACE; int i1, i2; @@ -384,7 +484,7 @@ namespace armarx } Eigen::Vector3f - GraspTrajectory::GetOrientationDerivative(float t) + GraspTrajectory::GetOrientationDerivative(float t) const { ARMARX_TRACE; int i1, i2; @@ -394,7 +494,7 @@ namespace armarx } Eigen::Matrix<float, 6, 1> - GraspTrajectory::GetTcpDerivative(float t) + GraspTrajectory::GetTcpDerivative(float t) const { ARMARX_TRACE; Eigen::Matrix<float, 6, 1> ffVel; @@ -404,7 +504,7 @@ namespace armarx } Eigen::Vector3f - GraspTrajectory::GetHandJointsDerivative(float t) + GraspTrajectory::GetHandJointsDerivative(float t) const { ARMARX_TRACE; int i1, i2; @@ -444,7 +544,7 @@ namespace armarx GraspTrajectoryPtr GraspTrajectory::getTranslatedAndRotated(const Eigen::Vector3f& translation, - const Eigen::Matrix3f& rotation) + const Eigen::Matrix3f& rotation) const { ARMARX_TRACE; GraspTrajectoryPtr traj( @@ -453,7 +553,7 @@ namespace armarx getKeypoint(0)->handJointsTarget)); for (size_t i = 1; i < keypoints.size(); i++) { - KeypointPtr& kp = keypoints.at(i); + const KeypointPtr& kp = keypoints.at(i); traj->addKeypoint( ::math::Helpers::TranslateAndRotatePose(kp->getTargetPose(), translation, rotation), kp->handJointsTarget, @@ -463,21 +563,21 @@ namespace armarx } GraspTrajectoryPtr - GraspTrajectory::getTransformed(const Eigen::Matrix4f& transform) + GraspTrajectory::getTransformed(const Eigen::Matrix4f& transform) const { ARMARX_TRACE; GraspTrajectoryPtr traj( new GraspTrajectory(transform * getStartPose(), getKeypoint(0)->handJointsTarget)); for (size_t i = 1; i < keypoints.size(); i++) { - KeypointPtr& kp = keypoints.at(i); + const KeypointPtr& kp = keypoints.at(i); traj->addKeypoint(transform * kp->getTargetPose(), kp->handJointsTarget, kp->dt); } return traj; } GraspTrajectoryPtr - GraspTrajectory::getClone() + GraspTrajectory::getClone() const { ARMARX_TRACE; return getTransformed(Eigen::Matrix4f::Identity()); @@ -485,7 +585,7 @@ namespace armarx GraspTrajectoryPtr GraspTrajectory::getTransformedToGraspPose(const Eigen::Matrix4f& target, - const Eigen::Vector3f& handForward) + const Eigen::Vector3f& handForward) const { ARMARX_TRACE; Eigen::Matrix4f startPose = getStartPose(); @@ -506,7 +606,7 @@ namespace armarx } GraspTrajectoryPtr - GraspTrajectory::getTransformedToOtherHand() + GraspTrajectory::getTransformedToOtherHand() const { ARMARX_TRACE; Eigen::Matrix3f flip_yz = Eigen::Matrix3f::Identity(); @@ -517,7 +617,7 @@ namespace armarx new GraspTrajectory(start_pose, getKeypoint(0)->handJointsTarget)); for (size_t i = 1; i < getKeypointCount(); i++) { - GraspTrajectory::KeypointPtr& kp = getKeypoint(i); + const GraspTrajectory::KeypointPtr& kp = getKeypoint(i); Eigen::Matrix4f target_pose = kp->getTargetPose(); target_pose.block<3, 3>(0, 0) = flip_yz * target_pose.block<3, 3>(0, 0) * flip_yz; output_trajectory->addKeypoint(target_pose, kp->handJointsTarget, kp->dt); @@ -592,14 +692,17 @@ namespace armarx return tcpTarget; } - GraspTrajectory::Keypoint::Keypoint(const Eigen::Matrix4f& tcpTarget, - const armarx::NameValueMap& handJointsTarget, - float dt, - const Eigen::Vector3f& feedForwardPosVelocity, - const Eigen::Vector3f& feedForwardOriVelocity, - const Eigen::VectorXf& feedForwardHandJointsVelocity) : + GraspTrajectoryKeypoint::GraspTrajectoryKeypoint( + const Eigen::Matrix4f& tcpTarget, + const armarx::NameValueMap& handJointsTarget, + float dt, + const Eigen::Vector3f& feedForwardPosVelocity, + const Eigen::Vector3f& feedForwardOriVelocity, + const Eigen::VectorXf& feedForwardHandJointsVelocity, + const std::optional<std::string>& shape) : tcpTarget(tcpTarget), handJointsTarget(handJointsTarget), + shape(shape), dt(dt), feedForwardPosVelocity(feedForwardPosVelocity), feedForwardOriVelocity(feedForwardOriVelocity), @@ -607,10 +710,12 @@ namespace armarx { } - GraspTrajectory::Keypoint::Keypoint(const Eigen::Matrix4f& tcpTarget, - const armarx::NameValueMap& handJointsTarget) : + GraspTrajectoryKeypoint::GraspTrajectoryKeypoint(const Eigen::Matrix4f& tcpTarget, + const armarx::NameValueMap& handJointsTarget, + const std::optional<std::string>& shape) : tcpTarget(tcpTarget), handJointsTarget(handJointsTarget), + shape(shape), dt(0), feedForwardPosVelocity(0, 0, 0), feedForwardOriVelocity(0, 0, 0) diff --git a/source/RobotAPI/libraries/GraspingUtility/GraspTrajectory.h b/source/RobotAPI/libraries/GraspingUtility/GraspTrajectory.h index 697727b22..718642c2a 100644 --- a/source/RobotAPI/libraries/GraspingUtility/GraspTrajectory.h +++ b/source/RobotAPI/libraries/GraspingUtility/GraspTrajectory.h @@ -41,34 +41,44 @@ namespace armarx class GraspTrajectory; typedef std::shared_ptr<GraspTrajectory> GraspTrajectoryPtr; - class GraspTrajectory + class GraspTrajectoryKeypoint { public: - class Keypoint; - typedef std::shared_ptr<Keypoint> KeypointPtr; + using GraspTrajectoryKeypointPtr = std::shared_ptr<GraspTrajectoryKeypoint>; + + Eigen::Matrix4f tcpTarget; + armarx::NameValueMap handJointsTarget; + std::optional<std::string> shape; + float dt; + Eigen::Vector3f feedForwardPosVelocity; + Eigen::Vector3f feedForwardOriVelocity; + Eigen::VectorXf feedForwardHandJointsVelocity; + + GraspTrajectoryKeypoint() = default; + + GraspTrajectoryKeypoint(const Eigen::Matrix4f& tcpTarget, + const armarx::NameValueMap& handJointsTarget, + const std::optional<std::string>& shape = std::nullopt); + + GraspTrajectoryKeypoint(const Eigen::Matrix4f& tcpTarget, + const armarx::NameValueMap& handJointsTarget, + float dt, + const Eigen::Vector3f& feedForwardPosVelocity, + const Eigen::Vector3f& feedForwardOriVelocity, + const Eigen::VectorXf& feedForwardHandJointsVelocity, + const std::optional<std::string>& shape = std::nullopt); + + Eigen::Vector3f getTargetPosition() const; + Eigen::Matrix3f getTargetOrientation() const; + Eigen::Matrix4f getTargetPose() const; + void updateVelocities(const GraspTrajectoryKeypointPtr& prev, float deltat); + }; - class Keypoint - { - public: - Eigen::Matrix4f tcpTarget; - armarx::NameValueMap handJointsTarget; - float dt; - Eigen::Vector3f feedForwardPosVelocity; - Eigen::Vector3f feedForwardOriVelocity; - Eigen::VectorXf feedForwardHandJointsVelocity; - - Keypoint(const Eigen::Matrix4f& tcpTarget, const armarx::NameValueMap& handJointsTarget); - Keypoint(const Eigen::Matrix4f& tcpTarget, - const armarx::NameValueMap& handJointsTarget, - float dt, - const Eigen::Vector3f& feedForwardPosVelocity, - const Eigen::Vector3f& feedForwardOriVelocity, - const Eigen::VectorXf& feedForwardHandJointsVelocity); - Eigen::Vector3f getTargetPosition() const; - Eigen::Matrix3f getTargetOrientation() const; - Eigen::Matrix4f getTargetPose() const; - void updateVelocities(const KeypointPtr& prev, float deltat); - }; + class GraspTrajectory + { + public: + using Keypoint = GraspTrajectoryKeypoint; + using KeypointPtr = std::shared_ptr<Keypoint>; struct Length { @@ -79,54 +89,62 @@ namespace armarx public: GraspTrajectory() = default; + GraspTrajectory(const std::vector<Keypoint>& keypoints); + GraspTrajectory(const Eigen::Matrix4f& tcpStart, - const armarx::NameValueMap& handJointsStart); + const armarx::NameValueMap& handJointsStart, + const std::optional<std::string>& shape = std::nullopt); void addKeypoint(const Eigen::Matrix4f& tcpTarget, const armarx::NameValueMap& handJointsTarget, - float dt); + float dt, + const std::optional<std::string>& shape = std::nullopt); size_t getKeypointCount() const; + const std::vector<KeypointPtr>& getAllKeypoints() const; void insertKeypoint(size_t index, const Eigen::Matrix4f& tcpTarget, const armarx::NameValueMap& handJointsTarget, - float dt); + float dt, + const std::optional<std::string>& shape = std::nullopt); void removeKeypoint(size_t index); void replaceKeypoint(size_t index, const Eigen::Matrix4f& tcpTarget, const armarx::NameValueMap& handJointsTarget, - float dt); + float dt, + const std::optional<std::string>& shape = std::nullopt); void setKeypointDt(size_t index, float dt); - KeypointPtr& lastKeypoint(); - KeypointPtr& getKeypoint(int i); - Eigen::Matrix4f getStartPose(); + const KeypointPtr& lastKeypoint() const; + const KeypointPtr& getKeypoint(int i) const; + Eigen::Matrix4f getStartPose() const; - void getIndex(float t, int& i1, int& i2, float& f); + void getIndex(float t, int& i1, int& i2, float& f) const; - Eigen::Vector3f GetPosition(float t); + Eigen::Vector3f GetPosition(float t) const; - Eigen::Matrix3f GetOrientation(float t); + Eigen::Matrix3f GetOrientation(float t) const; - Eigen::Matrix4f GetPose(float t); + Eigen::Matrix4f GetPose(float t) const; - std::vector<Eigen::Matrix4f> getAllKeypointPoses(); - std::vector<Eigen::Vector3f> getAllKeypointPositions(); - std::vector<Eigen::Matrix3f> getAllKeypointOrientations(); + std::vector<Eigen::Matrix4f> getAllKeypointPoses() const; + std::vector<Eigen::Vector3f> getAllKeypointPositions() const; + std::vector<Eigen::Matrix3f> getAllKeypointOrientations() const; - armarx::NameValueMap GetHandValues(float t); + armarx::NameValueMap GetHandValues(float t) const; + std::optional<std::string> GetShape(float t) const; - Eigen::Vector3f GetPositionDerivative(float t); + Eigen::Vector3f GetPositionDerivative(float t) const; - Eigen::Vector3f GetOrientationDerivative(float t); + Eigen::Vector3f GetOrientationDerivative(float t) const; - Eigen::Matrix<float, 6, 1> GetTcpDerivative(float t); + Eigen::Matrix<float, 6, 1> GetTcpDerivative(float t) const; - Eigen::Vector3f GetHandJointsDerivative(float t); + Eigen::Vector3f GetHandJointsDerivative(float t) const; float getDuration() const; @@ -134,15 +152,15 @@ namespace armarx GraspTrajectoryPtr getTranslatedAndRotated(const Eigen::Vector3f& translation, - const Eigen::Matrix3f& rotation); - GraspTrajectoryPtr getTransformed(const Eigen::Matrix4f& transform); - GraspTrajectoryPtr getTransformedToOtherHand(); + const Eigen::Matrix3f& rotation) const; + GraspTrajectoryPtr getTransformed(const Eigen::Matrix4f& transform) const; + GraspTrajectoryPtr getTransformedToOtherHand() const; - GraspTrajectoryPtr getClone(); + GraspTrajectoryPtr getClone() const; - GraspTrajectoryPtr - getTransformedToGraspPose(const Eigen::Matrix4f& target, - const Eigen::Vector3f& handForward = Eigen::Vector3f::UnitZ()); + GraspTrajectoryPtr getTransformedToGraspPose( + const Eigen::Matrix4f& target, + const Eigen::Vector3f& handForward = Eigen::Vector3f::UnitZ()) const; SimpleDiffIK::Reachability calculateReachability(VirtualRobot::RobotNodeSetPtr rns, @@ -154,6 +172,7 @@ namespace armarx static GraspTrajectoryPtr ReadFromReader(const RapidXmlReaderPtr& reader); static GraspTrajectoryPtr ReadFromFile(const std::string& filename); + static GraspTrajectoryPtr ReadFromJSON(const std::string& filename); static GraspTrajectoryPtr ReadFromString(const std::string& xml); private: -- GitLab