21
21
#include " autoware/path_optimizer/common_structs.hpp"
22
22
#include " autoware/path_optimizer/state_equation_generator.hpp"
23
23
#include " autoware/path_optimizer/type_alias.hpp"
24
+ #include " autoware/path_optimizer/utils/conditional_timer.hpp"
24
25
#include " autoware_utils/geometry/geometry.hpp"
25
26
#include " autoware_utils/system/time_keeper.hpp"
26
27
#include " autoware_vehicle_info_utils/vehicle_info_utils.hpp"
@@ -57,6 +58,15 @@ struct Bounds
57
58
lower_bound -= offset;
58
59
upper_bound -= offset;
59
60
}
61
+
62
+ friend std::ostream & operator <<(std::ostream & os, const Bounds & bounds)
63
+ {
64
+ os << " Bounds: {\n " ;
65
+ os << " \t lower_bound: " << bounds.lower_bound << " ,\n " ;
66
+ os << " \t upper_bound: " << bounds.upper_bound << " \n " ;
67
+ os << " }\n " ;
68
+ return os;
69
+ }
60
70
};
61
71
62
72
struct KinematicState
@@ -65,6 +75,15 @@ struct KinematicState
65
75
double yaw{0.0 };
66
76
67
77
Eigen::Vector2d toEigenVector () const { return Eigen::Vector2d{lat, yaw}; }
78
+
79
+ friend std::ostream & operator <<(std::ostream & os, const KinematicState & state)
80
+ {
81
+ os << " KinematicState: {\n " ;
82
+ os << " \t lat: " << state.lat << " ,\n " ;
83
+ os << " \t yaw: " << state.yaw << " \n " ;
84
+ os << " }\n " ;
85
+ return os;
86
+ }
68
87
};
69
88
70
89
struct ReferencePoint
@@ -92,6 +111,55 @@ struct ReferencePoint
92
111
93
112
double getYaw () const { return tf2::getYaw (pose.orientation ); }
94
113
114
+ friend std::ostream & operator <<(std::ostream & os, const ReferencePoint & ref_point)
115
+ {
116
+ os << " ReferencePoint: {\n " ;
117
+ os << " \t pose: " << ref_point.pose .position .x << " , " << ref_point.pose .position .y << " ,\n " ;
118
+ os << " \t longitudinal_velocity_mps: " << ref_point.longitudinal_velocity_mps << " ,\n " ;
119
+ os << " \t curvature: " << ref_point.curvature << " ,\n " ;
120
+ os << " \t delta_arc_length: " << ref_point.delta_arc_length << " ,\n " ;
121
+ os << " \t alpha: " << ref_point.alpha << " ,\n " ;
122
+ os << " \t bounds: " << ref_point.bounds << " ,\n " ;
123
+ os << " \t beta: [" ;
124
+ for (const auto & b : ref_point.beta ) {
125
+ os << b << " , " ;
126
+ }
127
+ os << " ],\n " ;
128
+ os << " \t normalized_avoidance_cost: " << ref_point.normalized_avoidance_cost << " ,\n " ;
129
+ os << " \t bounds_on_constraints: [" ;
130
+ for (const auto & b : ref_point.bounds_on_constraints ) {
131
+ os << b << " , " ;
132
+ }
133
+ os << " ],\n " ;
134
+ os << " \t pose_on_constraints: [" ;
135
+ for (const auto & p : ref_point.pose_on_constraints ) {
136
+ os << " (" << p.position .x << " , " << p.position .y << " ) , " ;
137
+ }
138
+ os << " ],\n " ;
139
+ os << " \t fixed_kinematic_state: " ;
140
+ if (ref_point.fixed_kinematic_state ) {
141
+ os << *ref_point.fixed_kinematic_state ;
142
+ } else {
143
+ os << " nullopt" ;
144
+ }
145
+ os << " ,\n " ;
146
+ os << " \t optimized_kinematic_state: " << ref_point.optimized_kinematic_state << " ,\n " ;
147
+ os << " \t optimized_input: " << ref_point.optimized_input << " ,\n " ;
148
+ os << " \t slack_variables: " ;
149
+ if (ref_point.slack_variables ) {
150
+ os << " [" ;
151
+ for (const auto & s : *ref_point.slack_variables ) {
152
+ os << s << " , " ;
153
+ }
154
+ os << " ]" ;
155
+ } else {
156
+ os << " nullopt" ;
157
+ }
158
+ os << " \n " ;
159
+ os << " }\n " ;
160
+ return os;
161
+ }
162
+
95
163
geometry_msgs::msg::Pose offsetDeviation (const double lat_dev, const double yaw_dev) const
96
164
{
97
165
auto pose_with_deviation = autoware_utils::calc_offset_pose (pose, 0.0 , lat_dev, 0.0 );
@@ -110,7 +178,7 @@ class MPTOptimizer
110
178
const TrajectoryParam & traj_param, const std::shared_ptr<DebugData> debug_data_ptr,
111
179
const std::shared_ptr<autoware_utils::TimeKeeper> time_keeper_);
112
180
113
- std::vector<TrajectoryPoint> optimizeTrajectory (const PlannerData & planner_data);
181
+ std::optional<std:: vector<TrajectoryPoint> > optimizeTrajectory (const PlannerData & planner_data);
114
182
std::optional<std::vector<TrajectoryPoint>> getPrevOptimizedTrajectoryPoints () const ;
115
183
116
184
void initialize (const bool enable_debug_info, const TrajectoryParam & traj_param);
@@ -126,19 +194,47 @@ class MPTOptimizer
126
194
{
127
195
Eigen::SparseMatrix<double > Q;
128
196
Eigen::SparseMatrix<double > R;
197
+
198
+ friend std::ostream & operator <<(std::ostream & os, const ValueMatrix & matrix)
199
+ {
200
+ os << " ValueMatrix: {\n " ;
201
+ os << " \t Q: (Sparse Matrix):" << matrix.Q ;
202
+ os << " \t R: (Sparse Matrix):" << matrix.R ;
203
+ os << " }\n " ;
204
+ return os;
205
+ }
129
206
};
130
207
131
208
struct ObjectiveMatrix
132
209
{
133
210
Eigen::MatrixXd hessian;
134
211
Eigen::VectorXd gradient;
212
+
213
+ friend std::ostream & operator <<(std::ostream & os, const ObjectiveMatrix & matrix)
214
+ {
215
+ os << " ObjectiveMatrix: {\n " ;
216
+ os << " \t hessian:\n " << matrix.hessian << " \n " ;
217
+ os << " \t gradient:\n " << matrix.gradient << " \n " ;
218
+ os << " }\n " ;
219
+ return os;
220
+ }
135
221
};
136
222
137
223
struct ConstraintMatrix
138
224
{
139
225
Eigen::MatrixXd linear;
140
226
Eigen::VectorXd lower_bound;
141
227
Eigen::VectorXd upper_bound;
228
+
229
+ friend std::ostream & operator <<(std::ostream & os, const ConstraintMatrix & matrix)
230
+ {
231
+ os << " ConstraintMatrix: {\n " ;
232
+ os << " \t linear:\n " << matrix.linear << " \n " ;
233
+ os << " \t lower_bound:\n " << matrix.lower_bound << " \n " ;
234
+ os << " \t upper_bound:\n " << matrix.upper_bound << " \n " ;
235
+ os << " }\n " ;
236
+ return os;
237
+ }
142
238
};
143
239
144
240
struct MPTParam
0 commit comments