Skip to content

Commit 9e96404

Browse files
committed
Merge branch 'feat/cuda_blackboard_centerpoint' of github.com:knzo25/autoware.universe into feat/cuda_blackboard_centerpoint
2 parents ffbfb88 + 68c61fd commit 9e96404

File tree

14 files changed

+259
-51
lines changed

14 files changed

+259
-51
lines changed

control/autoware_mpc_lateral_controller/src/qp_solver/qp_solver_osqp.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -54,11 +54,11 @@ bool QPSolverOSQP::solve(
5454
/* execute optimization */
5555
auto result = osqpsolver_.optimize(h_mat, osqpA, f, lower_bound, upper_bound);
5656

57-
std::vector<double> U_osqp = std::get<0>(result);
57+
std::vector<double> U_osqp = result.primal_solution;
5858
u = Eigen::Map<Eigen::Matrix<double, Eigen::Dynamic, 1>>(
5959
&U_osqp[0], static_cast<Eigen::Index>(U_osqp.size()), 1);
6060

61-
const int status_val = std::get<3>(result);
61+
const int status_val = result.solution_status;
6262
if (status_val != 1) {
6363
RCLCPP_WARN(logger_, "optimization failed : %s", osqpsolver_.getStatusMessage().c_str());
6464
return false;
@@ -71,7 +71,7 @@ bool QPSolverOSQP::solve(
7171
}
7272

7373
// polish status: successful (1), unperformed (0), (-1) unsuccessful
74-
int status_polish = std::get<2>(result);
74+
int status_polish = result.polish_status;
7575
if (status_polish == -1 || status_polish == 0) {
7676
const auto s = (status_polish == 0) ? "Polish process is not performed in osqp."
7777
: "Polish process failed in osqp.";

planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/velocity_optimizer.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -246,10 +246,11 @@ VelocityOptimizer::OptimizationResult VelocityOptimizer::optimize(const Optimiza
246246
}
247247

248248
// execute optimization
249-
const auto result = qp_solver_.optimize(P, A, q, lower_bound, upper_bound);
250-
const std::vector<double> optval = std::get<0>(result);
249+
const autoware::osqp_interface::OSQPResult result =
250+
qp_solver_.optimize(P, A, q, lower_bound, upper_bound);
251+
const std::vector<double> optval = result.primal_solution;
251252

252-
const int status_val = std::get<3>(result);
253+
const int status_val = result.solution_status;
253254
if (status_val != 1)
254255
std::cerr << "optimization failed : " << qp_solver_.getStatusMessage().c_str() << std::endl;
255256

planning/autoware_path_optimizer/include/autoware/path_optimizer/mpt_optimizer.hpp

+97-1
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include "autoware/path_optimizer/common_structs.hpp"
2222
#include "autoware/path_optimizer/state_equation_generator.hpp"
2323
#include "autoware/path_optimizer/type_alias.hpp"
24+
#include "autoware/path_optimizer/utils/conditional_timer.hpp"
2425
#include "autoware_utils/geometry/geometry.hpp"
2526
#include "autoware_utils/system/time_keeper.hpp"
2627
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
@@ -57,6 +58,15 @@ struct Bounds
5758
lower_bound -= offset;
5859
upper_bound -= offset;
5960
}
61+
62+
friend std::ostream & operator<<(std::ostream & os, const Bounds & bounds)
63+
{
64+
os << "Bounds: {\n";
65+
os << "\tlower_bound: " << bounds.lower_bound << ",\n";
66+
os << "\tupper_bound: " << bounds.upper_bound << "\n";
67+
os << "}\n";
68+
return os;
69+
}
6070
};
6171

6272
struct KinematicState
@@ -65,6 +75,15 @@ struct KinematicState
6575
double yaw{0.0};
6676

6777
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 << "\tlat: " << state.lat << ",\n";
83+
os << "\tyaw: " << state.yaw << "\n";
84+
os << "}\n";
85+
return os;
86+
}
6887
};
6988

7089
struct ReferencePoint
@@ -92,6 +111,55 @@ struct ReferencePoint
92111

93112
double getYaw() const { return tf2::getYaw(pose.orientation); }
94113

114+
friend std::ostream & operator<<(std::ostream & os, const ReferencePoint & ref_point)
115+
{
116+
os << "ReferencePoint: {\n";
117+
os << "\tpose: " << ref_point.pose.position.x << ", " << ref_point.pose.position.y << ",\n";
118+
os << "\tlongitudinal_velocity_mps: " << ref_point.longitudinal_velocity_mps << ",\n";
119+
os << "\tcurvature: " << ref_point.curvature << ",\n";
120+
os << "\tdelta_arc_length: " << ref_point.delta_arc_length << ",\n";
121+
os << "\talpha: " << ref_point.alpha << ",\n";
122+
os << "\tbounds: " << ref_point.bounds << ",\n";
123+
os << "\tbeta: [";
124+
for (const auto & b : ref_point.beta) {
125+
os << b << ", ";
126+
}
127+
os << "],\n";
128+
os << "\tnormalized_avoidance_cost: " << ref_point.normalized_avoidance_cost << ",\n";
129+
os << "\tbounds_on_constraints: [";
130+
for (const auto & b : ref_point.bounds_on_constraints) {
131+
os << b << ", ";
132+
}
133+
os << "],\n";
134+
os << "\tpose_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 << "\tfixed_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 << "\toptimized_kinematic_state: " << ref_point.optimized_kinematic_state << ",\n";
147+
os << "\toptimized_input: " << ref_point.optimized_input << ",\n";
148+
os << "\tslack_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+
95163
geometry_msgs::msg::Pose offsetDeviation(const double lat_dev, const double yaw_dev) const
96164
{
97165
auto pose_with_deviation = autoware_utils::calc_offset_pose(pose, 0.0, lat_dev, 0.0);
@@ -110,7 +178,7 @@ class MPTOptimizer
110178
const TrajectoryParam & traj_param, const std::shared_ptr<DebugData> debug_data_ptr,
111179
const std::shared_ptr<autoware_utils::TimeKeeper> time_keeper_);
112180

113-
std::vector<TrajectoryPoint> optimizeTrajectory(const PlannerData & planner_data);
181+
std::optional<std::vector<TrajectoryPoint>> optimizeTrajectory(const PlannerData & planner_data);
114182
std::optional<std::vector<TrajectoryPoint>> getPrevOptimizedTrajectoryPoints() const;
115183

116184
void initialize(const bool enable_debug_info, const TrajectoryParam & traj_param);
@@ -126,19 +194,47 @@ class MPTOptimizer
126194
{
127195
Eigen::SparseMatrix<double> Q;
128196
Eigen::SparseMatrix<double> R;
197+
198+
friend std::ostream & operator<<(std::ostream & os, const ValueMatrix & matrix)
199+
{
200+
os << "ValueMatrix: {\n";
201+
os << "\tQ: (Sparse Matrix):" << matrix.Q;
202+
os << "\tR: (Sparse Matrix):" << matrix.R;
203+
os << "}\n";
204+
return os;
205+
}
129206
};
130207

131208
struct ObjectiveMatrix
132209
{
133210
Eigen::MatrixXd hessian;
134211
Eigen::VectorXd gradient;
212+
213+
friend std::ostream & operator<<(std::ostream & os, const ObjectiveMatrix & matrix)
214+
{
215+
os << "ObjectiveMatrix: {\n";
216+
os << "\thessian:\n" << matrix.hessian << "\n";
217+
os << "\tgradient:\n" << matrix.gradient << "\n";
218+
os << "}\n";
219+
return os;
220+
}
135221
};
136222

137223
struct ConstraintMatrix
138224
{
139225
Eigen::MatrixXd linear;
140226
Eigen::VectorXd lower_bound;
141227
Eigen::VectorXd upper_bound;
228+
229+
friend std::ostream & operator<<(std::ostream & os, const ConstraintMatrix & matrix)
230+
{
231+
os << "ConstraintMatrix: {\n";
232+
os << "\tlinear:\n" << matrix.linear << "\n";
233+
os << "\tlower_bound:\n" << matrix.lower_bound << "\n";
234+
os << "\tupper_bound:\n" << matrix.upper_bound << "\n";
235+
os << "}\n";
236+
return os;
237+
}
142238
};
143239

144240
struct MPTParam

planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp

+8
Original file line numberDiff line numberDiff line change
@@ -20,13 +20,15 @@
2020
#include "autoware/path_optimizer/mpt_optimizer.hpp"
2121
#include "autoware/path_optimizer/replan_checker.hpp"
2222
#include "autoware/path_optimizer/type_alias.hpp"
23+
#include "autoware/path_optimizer/utils/conditional_timer.hpp"
2324
#include "autoware_utils/ros/logger_level_configure.hpp"
2425
#include "autoware_utils/ros/polling_subscriber.hpp"
2526
#include "autoware_utils/system/stop_watch.hpp"
2627
#include "autoware_utils/system/time_keeper.hpp"
2728
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
2829

2930
#include <autoware_utils/ros/published_time_publisher.hpp>
31+
#include <diagnostic_updater/diagnostic_updater.hpp>
3032
#include <rclcpp/publisher.hpp>
3133

3234
#include <algorithm>
@@ -68,6 +70,7 @@ class PathOptimizer : public rclcpp::Node
6870
autoware::vehicle_info_utils::VehicleInfo vehicle_info_{};
6971
mutable std::shared_ptr<DebugData> debug_data_ptr_{nullptr};
7072
mutable std::shared_ptr<autoware_utils::TimeKeeper> time_keeper_{nullptr};
73+
mutable std::shared_ptr<ConditionalTimer> conditional_timer_{nullptr};
7174

7275
// flags for some functions
7376
bool enable_pub_debug_marker_;
@@ -76,6 +79,7 @@ class PathOptimizer : public rclcpp::Node
7679
bool enable_outside_drivable_area_stop_;
7780
bool enable_skip_optimization_;
7881
bool enable_reset_prev_optimization_;
82+
bool is_optimization_failed_{false};
7983
bool use_footprint_polygon_for_outside_drivable_area_check_;
8084

8185
// core algorithms
@@ -123,6 +127,7 @@ class PathOptimizer : public rclcpp::Node
123127
const std::vector<TrajectoryPoint> & traj_points,
124128
const std::vector<TrajectoryPoint> & optimized_points) const;
125129
void publishDebugData(const Header & header) const;
130+
void onCheckPathOptimizationValid(diagnostic_updater::DiagnosticStatusWrapper & stat);
126131

127132
// functions in generateOptimizedTrajectory
128133
std::vector<TrajectoryPoint> optimizeTrajectory(const PlannerData & planner_data);
@@ -145,6 +150,9 @@ class PathOptimizer : public rclcpp::Node
145150
std::unique_ptr<autoware_utils::PublishedTimePublisher> published_time_publisher_;
146151

147152
autoware_utils::StopWatch<std::chrono::milliseconds> stop_watch_;
153+
154+
// diag
155+
diagnostic_updater::Updater updater_{this};
148156
};
149157
} // namespace autoware::path_optimizer
150158

planning/autoware_path_optimizer/include/autoware/path_optimizer/state_equation_generator.hpp

+10
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,16 @@ class StateEquationGenerator
3737
Eigen::VectorXd W;
3838
};
3939

40+
friend std::ostream & operator<<(std::ostream & os, const Matrix & matrix)
41+
{
42+
os << "Matrix: {\n";
43+
os << "\tA:\n" << matrix.A << "\n";
44+
os << "\tB:\n" << matrix.B << "\n";
45+
os << "\tW:\n" << matrix.W << "\n";
46+
os << "}\n";
47+
return os;
48+
}
49+
4050
StateEquationGenerator() = default;
4151
StateEquationGenerator(
4252
const double wheel_base, const double max_steer_rad,
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,48 @@
1+
// Copyright 2025 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#pragma once
16+
17+
#include <chrono>
18+
#include <optional>
19+
20+
class ConditionalTimer
21+
{
22+
public:
23+
void update(bool condition)
24+
{
25+
if (condition && !start_time_.has_value()) {
26+
// Condition met, start the timer
27+
start_time_ = std::chrono::high_resolution_clock::now();
28+
} else if (!condition && start_time_.has_value()) {
29+
// Condition no longer met, stop the timer
30+
start_time_ = std::nullopt;
31+
}
32+
}
33+
34+
std::chrono::duration<double> getElapsedTime() const
35+
{
36+
if (start_time_.has_value()) {
37+
auto current_time = std::chrono::high_resolution_clock::now();
38+
return current_time - *start_time_;
39+
} else {
40+
return std::chrono::duration<double>(0.0);
41+
;
42+
}
43+
}
44+
45+
private:
46+
std::optional<std::chrono::time_point<std::chrono::high_resolution_clock>> start_time_{
47+
std::nullopt};
48+
};

0 commit comments

Comments
 (0)