OrientationOptimizer.cpp
Go to the documentation of this file.
1 #include "OrientationOptimizer.h"
2 
3 #include <math.h>
4 
5 #include <algorithm>
6 #include <cmath>
7 #include <cstddef>
8 #include <vector>
9 
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>
13 
15 
18 
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>
24 
26 {
28  const Params& params) :
29  trajectory(trajectory), params(params)
30  {
31  }
32 
35  {
36  namespace r = ::ranges;
37  namespace rv = ::ranges::views;
38 
39  const auto toYaw = [](const core::GlobalTrajectoryPoint& pt) -> double
40  { return simox::math::mat4f_to_xyyaw(pt.waypoint.pose.matrix()).z(); };
41 
42  //orientations vector contains variable values that are changed during optimization. these
43  // values are changed to fit the given optimization criteria as good as possible
44  std::vector<double> orientations =
45  trajectory.points() | ranges::views::transform(toYaw) | ranges::to_vector;
46 
47  //the optimization tries to stay close to the movement direction, thus the original
48  // orientation is copied (it is expected that original orientation values are oriented
49  // so that they face along the trajectory)
50  const std::vector<double> inMovementDir = orientations;
51 
52  //calculate angle increment necessary for initial equidistant scattering of 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
58  {
59  if (params.predefinedRotationDirection)
60  {
61  switch (params.predefinedRotationDirection.value())
62  {
64  if (signedAngleDiff <= 0)
65  {
66  return signedAngleDiff;
67  }
68  return -2 * M_PI + signedAngleDiff;
69 
71  if (signedAngleDiff >= 0)
72  {
73  return signedAngleDiff;
74  }
75  return 2 * M_PI + signedAngleDiff;
76  }
77  }
78  return signedAngleDiff;
79  }();
80  const double angleIncrement = signedAngleDiffDesired / (orientations.size() - 1);
81 
82  //equidistant orientations are used as starting value for the optimization of the
83  // orientations in the first iteration
84  const std::vector<double> equidistantOrientations = [&]
85  {
86  std::vector<double> vec{orientations.front()};
87  for (std::size_t i = 1; i < orientations.size() - 1; i++)
88  {
89  vec.push_back(startOrientation + angleIncrement * i);
90  }
91  vec.push_back(orientations.back());
92  return vec;
93  }();
94  orientations = equidistantOrientations;
95 
96  /* //COMMENT IN FOR TEST CASE PLOTTING
97  std::vector<double> initial = orientations;
98  std::vector<double> prior = inMovementDir; */
99 
100  const float movementDirWeightStep =
101  (params.movementDirWeightEnd - params.movementDirWeightStart) / (params.iterations - 1);
102 
103  //iteratively optimize the orientations with increasing movementDirWeight, thus at first ignoring
104  // the criteria to look in the movement direction and slowly considering this more and more
105  // with each iteration
106  for (int it = 0; it < params.iterations; it++)
107  {
108  const float movementDirWeight =
109  params.iterations == 1 ? params.movementDirWeightEnd
110  : params.movementDirWeightStart + it * movementDirWeightStep;
111 
112  //interpolate orientation in walking direction and current orientation at walkingDirAlpha.
113  // interpolated values are used as starting values for next iteration
114  for (std::size_t i = 1; i < orientations.size() - 1; i++)
115  {
116  const float walkingDirAlpha = 0.2;
117 
118  const Eigen::Vector2f vMovementDir =
119  walkingDirAlpha *
120  (Eigen::Rotation2Df(inMovementDir.at(i)) * Eigen::Vector2f::UnitX());
121 
122  const Eigen::Vector2f vStartGoal =
123  (1.0 - walkingDirAlpha) *
124  (Eigen::Rotation2Df(orientations.at(i)) * Eigen::Vector2f::UnitX());
125 
126  const Eigen::Vector2f vCombined = [&]() -> Eigen::Vector2f
127  {
128  if (movementDirWeight > 0) // should rotate into movement direction?
129  {
130  return vMovementDir + vStartGoal;
131  }
132 
133  return vStartGoal;
134  }();
135  orientations.at(i) = std::atan2(vCombined.y(), vCombined.x());
136  }
137 
138  /* //COMMENT IN FOR TEST CASE PLOTTING
139  initial = orientations;
140  prior = inMovementDir; */
141 
142  const std::size_t nPoints = orientations.size();
143 
144  ceres::Problem problem;
145 
146  ARMARX_VERBOSE << orientations.size() - 2 << " orientations to optimize";
147 
148 
149  //--------------------------------------------------------------------------------------
150  // Start of Optimization Criteria
151 
152  // TODO https://ceres-solver.googlesource.com/ceres-solver/+/master/examples/slam/pose_graph_2d/pose_graph_2d.cc
153  // ceres::LocalParameterization* angle_local_parameterization =
154  // ceres::AngleLocalParameterization::Create();
155 
156  // keeps the new orientations somewhat close to the orientation in movement direction
157  if (movementDirWeight > 0.F)
158  {
159  ARMARX_VERBOSE << "Optimize: movement dir enabled.";
160  for (size_t i = 1; i < (orientations.size() - 1); i++)
161  {
162  float actualMovementDirWeight = movementDirWeight;
163  //the first and last four points should not consider it too much to look in the
164  // direction of the trajectory as the robot should not move too much when
165  // close to start or goal
166  if (i < 5)
167  {
168  actualMovementDirWeight *= i / 5.;
169  }
170  else if ((orientations.size() - i - 1) < 5)
171  {
172  actualMovementDirWeight *= (orientations.size() - i - 1) / 5.;
173  }
174 
175  ceres::CostFunction* movementDirCostFunction = new OrientationPriorCostFunctor(
176  inMovementDir.at(i), actualMovementDirWeight);
177 
178  ARMARX_DEBUG << "Adding OrientationPriorCostFunctor to optimize " << i;
179  problem.AddResidualBlock(movementDirCostFunction, nullptr, &orientations.at(i));
180  }
181  }
182 
183  // smooth waypoint orientation, no start and goal nodes involved!
184  if (params.smoothnessWeight > 0.F)
185  {
186  ARMARX_VERBOSE << "Enabled SmoothOrientationCost";
187  for (size_t i = 2; i < (orientations.size() - 2); i++)
188  {
189  ceres::CostFunction* smoothCostFunction =
191 
192  ARMARX_DEBUG << "Addding SmoothOrientationCostFunctor to optimize " << i - 1
193  << ", " << i << " and " << i + 1;
194  problem.AddResidualBlock(smoothCostFunction,
195  nullptr,
196  &orientations.at(i - 1),
197  &orientations.at(i),
198  &orientations.at(i + 1));
199  }
200  }
201 
202  // within a certain range close to the start, the robot shouldn't change its orientation
203  if (params.priorStartWeight > 0.F)
204  {
205  ARMARX_VERBOSE << "prior start enabled";
206  const auto connectedPointsInRangeStart =
208 
209  for (const size_t i : connectedPointsInRangeStart)
210  {
211  // skip the points that belong to the second half of the trajectory
212  if (i >= orientations.size() / 2)
213  {
214  continue;
215  }
216 
217  ceres::CostFunction* priorCostFunction = new OrientationPriorCostFunctor(
218  inMovementDir.front(), params.priorStartWeight);
219 
220  ARMARX_DEBUG << "Addding OrientationPriorCostFunctor(start) to optimize " << i;
221  problem.AddResidualBlock(priorCostFunction, nullptr, &orientations.at(i));
222  }
223  }
224 
225  // within a certain range close to the end, the robot shouldn't change its orientation
226  if (params.priorEndWeight > 0.F)
227  {
228  ARMARX_VERBOSE << "prior end enabled";
229 
230  const auto connectedPointsInRangeGoal = trajectory.allConnectedPointsInRange(
231  trajectory.poses().size() - 1, params.startGoalDistanceThreshold);
232 
233  for (const size_t i : connectedPointsInRangeGoal)
234  {
235  // skip the points that belong to the first half of the trajectory
236  if (i < orientations.size() / 2)
237  {
238  continue;
239  }
240 
241  ceres::CostFunction* priorCostFunction = new OrientationPriorCostFunctor(
242  inMovementDir.back(), params.priorEndWeight);
243 
244  ARMARX_DEBUG << "Addding OrientationPriorCostFunctor to optimize " << i;
245  problem.AddResidualBlock(priorCostFunction, nullptr, &orientations.at(i));
246  }
247  }
248 
249 
250  // smooth waypoint orientation, involving start
251  if (params.smoothnessWeightStartGoal > 0.F and nPoints > 3)
252  {
253  ARMARX_VERBOSE << "Enabled SmoothOrientationFixedPreCost";
254 
255  ceres::CostFunction* smoothCostFunction = new SmoothOrientationFixedPreCostFunctor(
256  orientations.front(), params.smoothnessWeightStartGoal);
257 
258  ARMARX_DEBUG << "Addding SmoothOrientationFixedPreCostFunctor to optimize 1 and 2";
259  problem.AddResidualBlock(
260  smoothCostFunction, nullptr, &orientations.at(1), &orientations.at(2));
261  }
262 
263  // smooth waypoint orientation, involving goal
264  if (params.smoothnessWeightStartGoal > 0.F and nPoints > 3)
265  {
266  ARMARX_VERBOSE << "Enabled SmoothOrientationFixedNextCost";
267 
268  ceres::CostFunction* smoothCostFunction = new SmoothOrientationFixedNextCostFunctor(
269  orientations.back(), params.smoothnessWeightStartGoal);
270 
271  ARMARX_DEBUG << "Addding SmoothOrientationFixedPreCostFunctor to optimize "
272  << orientations.size() - 3 << " and " << orientations.size() - 2;
273  problem.AddResidualBlock(smoothCostFunction,
274  nullptr,
275  &orientations.at(orientations.size() - 3),
276  &orientations.at(orientations.size() - 2));
277  }
278 
279  // End of Optimization Criteria
280  //--------------------------------------------------------------------------------------
281 
282  // Run the solver!
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;
288  // options.check_gradients = false;
289  // options.trust_region_minimizer_iterations_to_dump = {0, 1, 2, 5, 10, 20};
290  // options.max_trust_region_radius = 0.05;
291  // options.initial_trust_region_radius = 0.01;
292 
293  ceres::Solver::Summary summary;
294  Solve(options, &problem, &summary);
295 
296  ARMARX_VERBOSE << summary.FullReport() << "\n";
297 
298  const auto clampInPlace = [](auto& val)
299  { val = simox::math::periodic_clamp(val, -M_PI, M_PI); };
300 
301  std::for_each(orientations.begin(), orientations.end(), clampInPlace);
302 
303  if (not summary.IsSolutionUsable())
304  {
305  ARMARX_ERROR << "Orientation optimization failed!";
306  // TODO write to file
307  }
308  }
309 
310  const auto applyOrientation = [](const auto& p) -> core::GlobalTrajectoryPoint
311  {
312  core::GlobalTrajectoryPoint tp = p.first;
313  const float yaw = p.second;
314 
315  tp.waypoint.pose.linear() = simox::math::rpy_to_mat3f(0.F, 0.F, yaw);
316 
317  return tp;
318  };
319 
320  // TODO(fabian.reister): could also be in-place
321  const auto modifiedTrajectory = rv::zip(trajectory.points(), orientations) |
322  rv::transform(applyOrientation) | r::to_vector;
323 
325  .trajectory = modifiedTrajectory,
326 
327  /* //COMMENT IN FOR TEST CASE PLOTTING
328  .initial = initial,
329  .prior = prior */
330 
331  };
332  }
333 
334 
335 } // namespace armarx::navigation::global_planning::optimization
armarx::navigation::core::GlobalTrajectory
Definition: Trajectory.h:70
armarx::navigation::global_planning::optimization
This file is part of ArmarX.
Definition: aron_conversions.h:11
armarx::navigation::core::Waypoint::pose
Pose pose
Definition: basic_types.h:50
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:187
armarx::navigation::core::GlobalTrajectoryPoint::waypoint
Waypoint waypoint
Definition: Trajectory.h:39
armarx::navigation::global_planning::optimization::OrientationOptimizerParams::priorStartWeight
float priorStartWeight
Definition: OrientationOptimizer.h:46
OrientationOptimizer.h
armarx::navigation::global_planning::optimization::OrientationOptimizer::optimize
OptimizationResult optimize()
Definition: OrientationOptimizer.cpp:34
armarx::navigation::global_planning::optimization::OrientationOptimizerParams::movementDirWeightEnd
float movementDirWeightEnd
Definition: OrientationOptimizer.h:41
cost_functions.h
armarx::navigation::global_planning::optimization::OrientationOptimizerParams::startGoalDistanceThreshold
float startGoalDistanceThreshold
Definition: OrientationOptimizer.h:49
math.h
armarx::navigation::core::GlobalTrajectoryPoint
Definition: Trajectory.h:37
armarx::navigation::global_planning::optimization::OrientationOptimizerParams
Definition: OrientationOptimizer.h:37
armarx::navigation::global_planning::optimization::OrientationOptimizer::OptimizationResult::trajectory
std::optional< core::GlobalTrajectory > trajectory
Definition: OrientationOptimizer.h:63
armarx::navigation::global_planning::optimization::OrientationOptimizerParams::iterations
int iterations
Definition: OrientationOptimizer.h:39
armarx::navigation::global_planning::optimization::RotationDirection::CounterClockwise
@ CounterClockwise
M_PI
#define M_PI
Definition: MathTools.h:17
armarx::navigation::global_planning::optimization::OrientationOptimizerParams::smoothnessWeightStartGoal
float smoothnessWeightStartGoal
Definition: OrientationOptimizer.h:44
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:184
armarx::navigation::global_planning::optimization::OrientationOptimizer::OrientationOptimizer
OrientationOptimizer(const core::GlobalTrajectory &trajectory, const Params &params)
Definition: OrientationOptimizer.cpp:27
armarx::navigation::global_planning::optimization::OrientationOptimizerParams::movementDirWeightStart
float movementDirWeightStart
Definition: OrientationOptimizer.h:40
armarx::navigation::global_planning::optimization::SmoothOrientationCostFunctor
Definition: cost_functions.h:188
armarx::navigation::core::GlobalTrajectory::poses
std::vector< Pose > poses() const noexcept
Definition: Trajectory.cpp:346
ARMARX_ERROR
#define ARMARX_ERROR
Definition: Logging.h:196
armarx::transform
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT >>
Convenience function (with less typing) to transform a container of type InputT into the same contain...
Definition: algorithm.h:351
armarx::navigation::global_planning::optimization::SmoothOrientationFixedNextCostFunctor
Definition: cost_functions.h:91
armarx::navigation::global_planning::optimization::SmoothOrientationFixedPreCostFunctor
Definition: cost_functions.h:31
armarx::navigation::global_planning::optimization::OrientationOptimizerParams::predefinedRotationDirection
std::optional< RotationDirection > predefinedRotationDirection
Definition: OrientationOptimizer.h:51
armarx::navigation::global_planning::optimization::OrientationOptimizerParams::priorEndWeight
float priorEndWeight
Definition: OrientationOptimizer.h:47
armarx::navigation::global_planning::optimization::OrientationPriorCostFunctor
Definition: cost_functions.h:149
F
Definition: ExportDialogControllerTest.cpp:18
armarx::navigation::core::GlobalTrajectory::allConnectedPointsInRange
Indices allConnectedPointsInRange(std::size_t idx, float radius) const
get all points within a certain radius that are directly connected to idx
Definition: Trajectory.cpp:790
armarx::navigation::global_planning::optimization::RotationDirection::Clockwise
@ Clockwise
Logging.h
Trajectory.h
armarx::navigation::global_planning::optimization::OrientationOptimizerParams::smoothnessWeight
float smoothnessWeight
Definition: OrientationOptimizer.h:43
armarx::navigation::core::GlobalTrajectory::points
const std::vector< GlobalTrajectoryPoint > & points() const
Definition: Trajectory.cpp:734
armarx::navigation::global_planning::optimization::OrientationOptimizer::OptimizationResult
Definition: OrientationOptimizer.h:61