diff --git a/source/armarx/navigation/core/Trajectory.cpp b/source/armarx/navigation/core/Trajectory.cpp index e1774afada179dc94358eacbb3d603fe2475cc1b..fc5c9b0ba2d7d2efc9516e1979ee04c62115517a 100644 --- a/source/armarx/navigation/core/Trajectory.cpp +++ b/source/armarx/navigation/core/Trajectory.cpp @@ -6,18 +6,6 @@ #include <iterator> #include <limits> -#include <range/v3/action/insert.hpp> -#include <range/v3/numeric/accumulate.hpp> -#include <range/v3/range/conversion.hpp> -#include <range/v3/view/all.hpp> -#include <range/v3/view/concat.hpp> -#include <range/v3/view/for_each.hpp> -#include <range/v3/view/group_by.hpp> -#include <range/v3/view/reverse.hpp> -#include <range/v3/view/sliding.hpp> -#include <range/v3/view/transform.hpp> -#include <range/v3/view/zip.hpp> - #include <Eigen/Core> #include <Eigen/Geometry> @@ -34,6 +22,17 @@ #include <armarx/navigation/conversions/eigen.h> #include <armarx/navigation/core/basic_types.h> #include <armarx/navigation/core/types.h> +#include <range/v3/action/insert.hpp> +#include <range/v3/numeric/accumulate.hpp> +#include <range/v3/range/conversion.hpp> +#include <range/v3/view/all.hpp> +#include <range/v3/view/concat.hpp> +#include <range/v3/view/for_each.hpp> +#include <range/v3/view/group_by.hpp> +#include <range/v3/view/reverse.hpp> +#include <range/v3/view/sliding.hpp> +#include <range/v3/view/transform.hpp> +#include <range/v3/view/zip.hpp> // FIXME move to simox @@ -158,13 +157,14 @@ namespace armarx::navigation::core } // namespace conv - Projection - GlobalTrajectory::getProjection(const Position& point, - const VelocityInterpolation& velocityInterpolation) const + + GlobalTrajectory::InternalProjection + GlobalTrajectory::projectInternal(const Position& point, + const VelocityInterpolation& velocityInterpolation) const { float distance = std::numeric_limits<float>::max(); - Projection bestProj; + InternalProjection bestProj; for (size_t i = 0; i < pts.size() - 1; i++) { @@ -198,26 +198,9 @@ namespace armarx::navigation::core math::LinearInterpolatedPose ip( wpBefore.waypoint.pose.matrix(), wpAfter.waypoint.pose.matrix(), 0, 1, true); - bestProj.wayPointBefore = wpBefore; - bestProj.wayPointAfter = wpAfter; + bestProj.indexBefore = i; bestProj.projection.waypoint.pose = ip.Get(t); - bestProj.segment = [&] - { - if (i == 0) - { - return Projection::Segment::FIRST; - } - - if (i == (pts.size() - 2)) - { - return Projection::Segment::FINAL; - } - - return Projection::Segment::INTERMEDIATE; - }(); - - switch (velocityInterpolation) { case VelocityInterpolation::LinearInterpolation: @@ -236,6 +219,82 @@ namespace armarx::navigation::core return bestProj; } + Projection + GlobalTrajectory::getProjection(const Position& point, + const VelocityInterpolation& velocityInterpolation) const + { + InternalProjection intProj = projectInternal(point, velocityInterpolation); + + const auto& wpBefore = pts.at(intProj.indexBefore); + const auto& wpAfter = pts.at(intProj.indexBefore + 1); + + Projection bestProj; + + bestProj.wayPointBefore = wpBefore; + bestProj.wayPointAfter = wpAfter; + bestProj.projection = intProj.projection; + + bestProj.segment = [&] + { + if (intProj.indexBefore == 0) + { + return Projection::Segment::FIRST; + } + + if (intProj.indexBefore == (pts.size() - 2)) + { + return Projection::Segment::FINAL; + } + + return Projection::Segment::INTERMEDIATE; + }(); + + return bestProj; + } + + std::pair<GlobalTrajectory, bool> + GlobalTrajectory::getSubTrajectory(const Position& point, float distance) const + { + const InternalProjection intProj = + projectInternal(point, VelocityInterpolation::LinearInterpolation); + + GlobalTrajectory subTraj{}; + subTraj.mutablePoints().push_back(intProj.projection); + + float remainingDistance = distance; + GlobalTrajectoryPoint lastWp = intProj.projection; + for (size_t i = intProj.indexBefore + 1; i < pts.size(); i++) + { + const auto& nextWp = pts.at(i); + + const float segmentDistance = + (nextWp.waypoint.pose.translation() - lastWp.waypoint.pose.translation()).norm(); + + if (segmentDistance < remainingDistance) + { + subTraj.mutablePoints().push_back(nextWp); + lastWp = nextWp; + remainingDistance -= segmentDistance; + } + else + { + // fraction of distance between segment end points + const float t = remainingDistance / segmentDistance; + + math::LinearInterpolatedPose ip( + lastWp.waypoint.pose.matrix(), nextWp.waypoint.pose.matrix(), 0, 1, true); + const float velocity = lastWp.velocity + (nextWp.velocity - lastWp.velocity) * t; + + subTraj.mutablePoints().push_back({{static_cast<Pose>(ip.Get(t))}, velocity}); + + return {subTraj, false}; + } + } + + // remaining trajectory is shorter than the specified distance + return {subTraj, true}; + } + std::vector<Eigen::Vector3f> GlobalTrajectory::positions() const noexcept { @@ -273,9 +332,9 @@ namespace armarx::navigation::core GlobalTrajectory GlobalTrajectory::FromPath(const Pose& start, - const Positions& waypoints, - const Pose& goal, - const float velocity) + const Positions& waypoints, + const Pose& goal, + const float velocity) { // currently, only 2D version @@ -331,7 +390,8 @@ namespace armarx::navigation::core { core::Positions resampledPath; - const auto toPoint = [](const GlobalTrajectoryPoint& wp) -> Pose { return wp.waypoint.pose; }; + const auto toPoint = [](const GlobalTrajectoryPoint& wp) -> Pose + { return wp.waypoint.pose; }; const core::Path originalPath = pts | ranges::views::transform(toPoint) | ranges::to_vector; @@ -601,7 +661,7 @@ namespace armarx::navigation::core constexpr int nSamples = 100; - for(int j = 0; j < nSamples; j++) + for (int j = 0; j < nSamples; j++) { const float progress = static_cast<float>(j) / nSamples; @@ -675,7 +735,6 @@ namespace armarx::navigation::core return indices; } - const std::vector<LocalTrajectoryPoint>& LocalTrajectory::points() const { @@ -714,14 +773,16 @@ namespace armarx::navigation::core // fraction of time between segment end points const float t = d1 / dT; - math::LinearInterpolatedPose ip(global_T_wp_before.matrix(), global_T_wp_after.matrix(), 0, 1, true); + math::LinearInterpolatedPose ip( + global_T_wp_before.matrix(), global_T_wp_after.matrix(), 0, 1, true); const core::Pose wp_before_T_wp_after = global_T_wp_before.inverse() * global_T_wp_after; const Eigen::Matrix3f& global_R_wp_before = global_T_wp_before.linear(); // the movement direction in the global frame - const Eigen::Vector3f global_V_linear_movement_direction = global_R_wp_before * wp_before_T_wp_after.translation().normalized(); + const Eigen::Vector3f global_V_linear_movement_direction = + global_R_wp_before * wp_before_T_wp_after.translation().normalized(); const Eigen::Vector3f distance = lower[1].pose.translation() - lower->pose.translation(); const float linearVelocity = static_cast<float>(distance.norm()) / dT.toSecondsDouble(); @@ -730,11 +791,9 @@ namespace armarx::navigation::core Eigen::AngleAxisf angleAx(wp_before_T_wp_after.linear()); - const core::Twist feedforwardTwist - { + const core::Twist feedforwardTwist{ .linear = linearVelocity * global_V_linear_movement_direction, - .angular = angleAx.axis() * angleAx.angle() / dT.toSecondsDouble() - }; + .angular = angleAx.axis() * angleAx.angle() / dT.toSecondsDouble()}; return {static_cast<core::Pose>(ip.Get(t)), feedforwardTwist}; } diff --git a/source/armarx/navigation/core/Trajectory.h b/source/armarx/navigation/core/Trajectory.h index 5b2ba33ab9482879bbc4e713286074f4a0de32cb..20da0ba1f577865ab3e7938a1dddb4f3e565275a 100644 --- a/source/armarx/navigation/core/Trajectory.h +++ b/source/armarx/navigation/core/Trajectory.h @@ -24,6 +24,7 @@ #include <cstddef> #include <memory> + #include "ArmarXCore/core/time/DateTime.h" #include <armarx/navigation/core/basic_types.h> @@ -76,6 +77,15 @@ namespace armarx::navigation::core Projection getProjection(const Position& point, const VelocityInterpolation& velocityInterpolation) const; + /** + * @brief Project point onto the trajectory and return a new trajectory along the old one + * from that point for the specified distance. + * @return The subtrajectory and whether the subtrajectory ends at the same point, + * as this trajectory + */ + std::pair<GlobalTrajectory, bool> getSubTrajectory(const Position& point, + const float distance) const; + [[nodiscard]] std::vector<Position> positions() const noexcept; [[nodiscard]] std::vector<Pose> poses() const noexcept; @@ -117,6 +127,16 @@ namespace armarx::navigation::core */ Indices allConnectedPointsInRange(std::size_t idx, float radius) const; + private: + struct InternalProjection + { + GlobalTrajectoryPoint projection; + size_t indexBefore; + }; + InternalProjection + projectInternal(const Position& point, + const VelocityInterpolation& velocityInterpolation) const; + private: std::vector<GlobalTrajectoryPoint> pts; diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp index f0495713816627b9a41ba4aa57cfd48c46cc791d..3ff39fd62e63d818d4b9b1f5aeedd6d2266aea84 100644 --- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp +++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp @@ -100,16 +100,20 @@ namespace armarx::navigation::local_planning std::optional<LocalPlannerResult> TimedElasticBands::plan(const core::GlobalTrajectory& goal) { - const teb_local_planner::TimedElasticBand globalPath = conv::toRos(goal); + const core::Pose currentPose{scene.robot->getGlobalPose()}; + + // TODO (SALt): put distance parameter into config (note: distance is in mm) + // prune global trajectory + const auto& [prunedGoal, planToDest] = + goal.getSubTrajectory(currentPose.translation(), 2000); + + const teb_local_planner::TimedElasticBand globalPath = conv::toRos(prunedGoal); teb_globalPath = globalPath.poses(); hcp_->setGlobalPath(&teb_globalPath); - const core::Pose currentPose{scene.robot->getGlobalPose()}; - const teb_local_planner::PoseSE2 start = conv::toRos(currentPose); - - const FindTargetResult target = findTarget(currentPose, goal); - const teb_local_planner::PoseSE2 end = conv::toRos(target.target); + const teb_local_planner::PoseSE2 end = + conv::toRos(prunedGoal.points().back().waypoint.pose); geometry_msgs::Twist velocity_start = conv::toRos(scene.platformVelocity); @@ -118,7 +122,8 @@ namespace armarx::navigation::local_planning try { - hcp_->plan(start, end, &velocity_start, !target.planToDestination); + // TODO (SALt): free goal velocity is not respected inside homotopy planner + hcp_->plan(start, end, &velocity_start, !planToDest); } catch (std::exception& e) { @@ -134,20 +139,6 @@ namespace armarx::navigation::local_planning } - TimedElasticBands::FindTargetResult - TimedElasticBands::findTarget(const core::Pose& currentPose, - const core::GlobalTrajectory& globalPath) - { - // TODO (SALt): implement - - const core::Projection projection = globalPath.getProjection( - currentPose.translation(), core::VelocityInterpolation::LinearInterpolation); - - return {conv::to2D(projection.projection.waypoint.pose), - conv::to2D(globalPath.points().back().waypoint.pose), - true}; - } - void TimedElasticBands::fillObstacles() { diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h index 26826650ec4ff1d7e667ba74dad48f3a0af39a04..f8c005aca06af92f6aadbc6da14241c82a9eee97 100644 --- a/source/armarx/navigation/local_planning/TimedElasticBands.h +++ b/source/armarx/navigation/local_planning/TimedElasticBands.h @@ -59,16 +59,7 @@ namespace armarx::navigation::local_planning std::optional<LocalPlannerResult> plan(const core::GlobalTrajectory& goal) override; private: - struct FindTargetResult - { - core::Pose2D projection; - core::Pose2D target; - bool planToDestination; - }; - void initConfig(); - FindTargetResult findTarget(const core::Pose& currentPose, - const core::GlobalTrajectory& globalPath); void fillObstacles(); protected: