10 #include <SimoxUtility/math/convert/mat4f_to_xyyaw.h>
11 #include <SimoxUtility/math/convert/rpy_to_mat3f.h>
12 #include <SimoxUtility/math/periodic/periodic_clamp.h>
19 #include <ceres/ceres.h>
20 #include <ceres/cost_function.h>
21 #include <range/v3/range/conversion.hpp>
22 #include <range/v3/view/transform.hpp>
23 #include <range/v3/view/zip.hpp>
29 trajectory(trajectory), params(params)
36 namespace r = ::ranges;
37 namespace rv = ::ranges::views;
40 {
return simox::math::mat4f_to_xyyaw(pt.waypoint.pose.matrix()).z(); };
44 std::vector<double> orientations =
50 const std::vector<double> inMovementDir = orientations;
53 const double& startOrientation = orientations.front();
54 const double& goalOrientation = orientations.back();
55 const double signedAngleDiff =
56 std::fmod<double>(goalOrientation - startOrientation + 3 *
M_PI, 2 *
M_PI) -
M_PI;
57 const double signedAngleDiffDesired = [&]() ->
double
64 if (signedAngleDiff <= 0)
66 return signedAngleDiff;
68 return -2 *
M_PI + signedAngleDiff;
71 if (signedAngleDiff >= 0)
73 return signedAngleDiff;
75 return 2 *
M_PI + signedAngleDiff;
78 return signedAngleDiff;
80 const double angleIncrement = signedAngleDiffDesired / (orientations.size() - 1);
84 const std::vector<double> equidistantOrientations = [&]
86 std::vector<double> vec{orientations.front()};
87 for (std::size_t i = 1; i < orientations.size() - 1; i++)
89 vec.push_back(startOrientation + angleIncrement * i);
91 vec.push_back(orientations.back());
94 orientations = equidistantOrientations;
100 const float movementDirWeightStep =
106 for (
int it = 0; it < params.
iterations; it++)
108 const float movementDirWeight =
114 for (std::size_t i = 1; i < orientations.size() - 1; i++)
116 const float walkingDirAlpha = 0.2;
118 const Eigen::Vector2f vMovementDir =
120 (Eigen::Rotation2Df(inMovementDir.at(i)) * Eigen::Vector2f::UnitX());
122 const Eigen::Vector2f vStartGoal =
123 (1.0 - walkingDirAlpha) *
124 (Eigen::Rotation2Df(orientations.at(i)) * Eigen::Vector2f::UnitX());
126 const Eigen::Vector2f vCombined = [&]() -> Eigen::Vector2f
128 if (movementDirWeight > 0)
130 return vMovementDir + vStartGoal;
135 orientations.at(i) = std::atan2(vCombined.y(), vCombined.x());
142 const std::size_t nPoints = orientations.size();
144 ceres::Problem problem;
146 ARMARX_VERBOSE << orientations.size() - 2 <<
" orientations to optimize";
157 if (movementDirWeight > 0.
F)
160 for (
size_t i = 1; i < (orientations.size() - 1); i++)
162 float actualMovementDirWeight = movementDirWeight;
168 actualMovementDirWeight *= i / 5.;
170 else if ((orientations.size() - i - 1) < 5)
172 actualMovementDirWeight *= (orientations.size() - i - 1) / 5.;
176 inMovementDir.at(i), actualMovementDirWeight);
178 ARMARX_DEBUG <<
"Adding OrientationPriorCostFunctor to optimize " << i;
179 problem.AddResidualBlock(movementDirCostFunction,
nullptr, &orientations.at(i));
187 for (
size_t i = 2; i < (orientations.size() - 2); i++)
189 ceres::CostFunction* smoothCostFunction =
192 ARMARX_DEBUG <<
"Addding SmoothOrientationCostFunctor to optimize " << i - 1
193 <<
", " << i <<
" and " << i + 1;
194 problem.AddResidualBlock(smoothCostFunction,
196 &orientations.at(i - 1),
198 &orientations.at(i + 1));
206 const auto connectedPointsInRangeStart =
209 for (
const size_t i : connectedPointsInRangeStart)
212 if (i >= orientations.size() / 2)
220 ARMARX_DEBUG <<
"Addding OrientationPriorCostFunctor(start) to optimize " << i;
221 problem.AddResidualBlock(priorCostFunction,
nullptr, &orientations.at(i));
233 for (
const size_t i : connectedPointsInRangeGoal)
236 if (i < orientations.size() / 2)
244 ARMARX_DEBUG <<
"Addding OrientationPriorCostFunctor to optimize " << i;
245 problem.AddResidualBlock(priorCostFunction,
nullptr, &orientations.at(i));
258 ARMARX_DEBUG <<
"Addding SmoothOrientationFixedPreCostFunctor to optimize 1 and 2";
259 problem.AddResidualBlock(
260 smoothCostFunction,
nullptr, &orientations.at(1), &orientations.at(2));
271 ARMARX_DEBUG <<
"Addding SmoothOrientationFixedPreCostFunctor to optimize "
272 << orientations.size() - 3 <<
" and " << orientations.size() - 2;
273 problem.AddResidualBlock(smoothCostFunction,
275 &orientations.at(orientations.size() - 3),
276 &orientations.at(orientations.size() - 2));
283 ceres::Solver::Options options;
284 options.linear_solver_type = ceres::DENSE_QR;
285 options.minimizer_progress_to_stdout =
false;
286 options.max_num_iterations = 100;
287 options.function_tolerance = 0.01;
293 ceres::Solver::Summary summary;
294 Solve(options, &problem, &summary);
298 const auto clampInPlace = [](
auto& val)
299 { val = simox::math::periodic_clamp(val, -
M_PI,
M_PI); };
301 std::for_each(orientations.begin(), orientations.end(), clampInPlace);
303 if (not summary.IsSolutionUsable())
313 const float yaw = p.second;
315 tp.
waypoint.
pose.linear() = simox::math::rpy_to_mat3f(0.
F, 0.
F, yaw);
321 const auto modifiedTrajectory = rv::zip(trajectory.
points(), orientations) |