Smoothing.cpp
Go to the documentation of this file.
1#include "Smoothing.h"
2
3#include <iomanip>
4
5#include <Eigen/Geometry>
6
8
12
14{
16 const Costmap3D& costmap3d,
17 const Params& params) :
18 trajectory(trajectory), params(params), costmap3d(costmap3d)
19 {
20 }
21
22 // convert back to global trajectory
24 toGlobalTrajectory(const std::vector<CenterPoint>& traj)
25 {
27 for (const auto& p : traj)
28 {
30 gp.waypoint.pose =
31 Eigen::Translation3f{Eigen::Vector3f(p.x, p.y, 0.0)} *
32 Eigen::AngleAxisf{static_cast<float>(p.theta), Eigen::Vector3f::UnitZ()};
33 gp.velocity = 200;
34 gtraj.mutablePoints().push_back(gp);
35 }
36 return gtraj;
37 }
38
39 // convert global trajectory to trajectory for smoothing
40 std::vector<CenterPoint>
42 {
43 std::vector<CenterPoint> traj;
44 for (const auto& gp : gtraj.points())
45 {
47 p.x = gp.waypoint.pose.translation().x();
48 p.y = gp.waypoint.pose.translation().y();
49 p.theta = gp.waypoint.pose.rotation().eulerAngles(0, 1, 2)[2];
50 p.v = gp.velocity;
51 traj.push_back(p);
52 }
53 return traj;
54 }
55
56 Smoothing::OptimizationResult
58 {
59 Costmap3DWrapper costmapWrapper{costmap3d};
60
61 // Convert trajectory (currently only a shortcut - not the correct trajectory is used)
62 std::vector<CenterPoint> traj;
63 std::vector<CenterPoint> traj_orig;
64 {
65 traj = toCenterTrajectory(trajectory);
66 traj_orig = traj;
67 }
68
69 optimizeTrajectoryCeres(traj, costmapWrapper, traj_orig, params);
70
71 for (int i = 0; i < static_cast<int>(traj.size()); ++i)
72 {
73 ARMARX_DEBUG << std::fixed << std::setprecision(3) << "i=" << i << " : x=" << traj[i].x
74 << " y=" << traj[i].y << " theta=" << traj[i].theta << " v=" << traj[i].v;
75 }
76
77 return {toGlobalTrajectory(traj)};
78 }
79
80 std::vector<core::GlobalTrajectoryPoint>
82 {
83 std::vector<core::GlobalTrajectoryPoint> collisionPoints;
84 for (const auto& p : centerTrajectory.points())
85 {
86 bool inCollision = costmap3d.isInCollision(
87 conv::to2D(p.waypoint.pose.translation()),
88 costmap3d.closestRotationFromDegrees(
89 costmap3d.rotationDegrees(conv::to2D(p.waypoint.pose))));
90 if (inCollision)
91 {
92 ARMARX_INFO << "Collision detected at position "
93 << VAROUT(conv::to2D(p.waypoint.pose).translation());
94 collisionPoints.push_back(p);
95 }
96 }
97 ARMARX_INFO << "Trajectory is "
98 << (collisionPoints.empty() ? "collision-free." : "in collision!");
99 return collisionPoints;
100 }
101
102
103} // namespace armarx::navigation::algorithms::orientation_aware::smoothing
#define VAROUT(x)
Smoothing(const core::GlobalTrajectory &trajectory, const Costmap3D &costmap3d, const Params &params)
Definition Smoothing.cpp:15
std::vector< core::GlobalTrajectoryPoint > checkCenterTrajectory(core::GlobalTrajectory &centerTrajectory) const
Definition Smoothing.cpp:81
const std::vector< GlobalTrajectoryPoint > & points() const
std::vector< GlobalTrajectoryPoint > & mutablePoints()
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
Definition Logging.h:184
std::vector< CenterPoint > toCenterTrajectory(const armarx::navigation::core::GlobalTrajectory &gtraj)
Definition Smoothing.cpp:41
armarx::navigation::core::GlobalTrajectory toGlobalTrajectory(const std::vector< CenterPoint > &traj)
Definition Smoothing.cpp:24
void optimizeTrajectoryCeres(std::vector< CenterPoint > &traj, const Costmap3DWrapper &costmap_wrapper, const std::vector< CenterPoint > &traj_original, const io::SmoothingParams &opts)
Definition residuals.h:375
std::vector< Eigen::Vector2f > to2D(const std::vector< Eigen::Vector3f > &v)
Definition eigen.cpp:29