Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit 4a8b586

Browse files
committedJun 26, 2024
Work on documentation
Signed-off-by: Simon Eisenmann <simon.eisenmann@driveblocks.ai>
1 parent 4af9b99 commit 4a8b586

File tree

12 files changed

+217
-232
lines changed

12 files changed

+217
-232
lines changed
 

‎planning/mapless_architecture/autoware_hmi/include/autoware/hmi/hmi_node.hpp

-7
Original file line numberDiff line numberDiff line change
@@ -27,10 +27,6 @@ class HMINode : public rclcpp::Node
2727
HMINode();
2828

2929
private:
30-
// ###########################################################################
31-
// # PRIVATE PROCESSING METHODS
32-
// ###########################################################################
33-
3430
/**
3531
* @brief Callback function for parameter changes.
3632
* This callback function is triggered whenever a ROS 2 parameter is changed.
@@ -46,9 +42,6 @@ class HMINode : public rclcpp::Node
4642
*/
4743
void PublishMission_(std::string mission);
4844

49-
// ###########################################################################
50-
// # PRIVATE VARIABLES
51-
// ###########################################################################
5245
// Declare ROS2 publisher and subscriber
5346

5447
rclcpp::Publisher<autoware_planning_msgs::msg::Mission>::SharedPtr mission_publisher_;

‎planning/mapless_architecture/autoware_hmi/src/hmi_node.cpp

-8
Original file line numberDiff line numberDiff line change
@@ -11,14 +11,6 @@ namespace autoware::mapless_architecture
1111
{
1212
using std::placeholders::_1;
1313

14-
/**
15-
16-
* @brief Constructor for the HMINode class.
17-
18-
* Initializes the publisher and subscriber with appropriate topics and QoS
19-
settings.
20-
21-
*/
2214
HMINode::HMINode() : Node("hmi_node")
2315
{
2416
// Set quality of service to best effort (if transmission fails, do not try to

‎planning/mapless_architecture/autoware_local_map_provider/include/autoware/local_map_provider/local_map_provider_node.hpp

-7
Original file line numberDiff line numberDiff line change
@@ -26,20 +26,13 @@ class LocalMapProviderNode : public rclcpp::Node
2626
LocalMapProviderNode();
2727

2828
private:
29-
// ###########################################################################
30-
// # PRIVATE PROCESSING METHODS
31-
// ###########################################################################
32-
3329
/**
3430
* @brief The callback for the RoadSegments messages.
3531
*
3632
* @param msg The autoware_planning_msgs::msg::RoadSegments message.
3733
*/
3834
void CallbackRoadSegmentsMessages_(const autoware_planning_msgs::msg::RoadSegments & msg);
3935

40-
// ###########################################################################
41-
// # PRIVATE VARIABLES
42-
// ###########################################################################
4336
// Declare ROS2 publisher and subscriber
4437

4538
rclcpp::Publisher<autoware_planning_msgs::msg::LocalMap>::SharedPtr map_publisher_;

‎planning/mapless_architecture/autoware_local_mission_planner/include/autoware/local_mission_planner/mission_planner_node.hpp

+7-12
Original file line numberDiff line numberDiff line change
@@ -30,14 +30,15 @@
3030
namespace autoware::mapless_architecture
3131
{
3232

33-
// Create Direction data type
33+
// Direction data type
3434
typedef int Direction;
3535
const Direction stay = 0;
3636
const Direction left = 1;
3737
const Direction right = 2;
3838
const Direction left_most = 3;
3939
const Direction right_most = 4;
4040

41+
// Define Lanes
4142
struct Lanes
4243
{
4344
std::vector<int> ego;
@@ -204,10 +205,6 @@ class MissionPlannerNode : public rclcpp::Node
204205
std::vector<LaneletConnection> & out_lanelet_connections);
205206

206207
private:
207-
// ###########################################################################
208-
// # PRIVATE PROCESSING METHODS
209-
// ###########################################################################
210-
211208
/**
212209
* @brief Function for the visualization of lanes.
213210
*
@@ -283,9 +280,6 @@ class MissionPlannerNode : public rclcpp::Node
283280
*/
284281
void CalculatePredecessors(std::vector<LaneletConnection> & lanelet_connections);
285282

286-
// ###########################################################################
287-
// # PRIVATE VARIABLES
288-
// ###########################################################################
289283
// Declare ROS2 publisher and subscriber
290284
rclcpp::Subscription<autoware_planning_msgs::msg::LocalMap>::SharedPtr mapSubscriber_;
291285

@@ -309,11 +303,12 @@ class MissionPlannerNode : public rclcpp::Node
309303
// ROS buffer interface (for TF transforms)
310304
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
311305
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
312-
// store previous odometry message
306+
307+
// Store previous odometry message
313308
nav_msgs::msg::Odometry last_odom_msg_;
314-
Pose2D pose_prev_;
315-
// Pose2D target_pose_ = {0.0, 0.0};
316309

310+
// Initialize some variables
311+
Pose2D pose_prev_;
317312
bool pose_prev_init_ = false;
318313
bool b_global_odometry_deprecation_warning_ = false;
319314
bool received_motion_update_once_ = false;
@@ -329,7 +324,7 @@ class MissionPlannerNode : public rclcpp::Node
329324
std::vector<int> lane_right_;
330325
std::vector<lanelet::Lanelet> current_lanelets_;
331326

332-
// ros parameters
327+
// ROS parameters
333328
float distance_to_centerline_threshold_;
334329
float projection_distance_on_goallane_;
335330
int retrigger_attempts_max_;

‎planning/mapless_architecture/autoware_local_mission_planner/test/src/test_mission_planner_core.cpp

+9-8
Original file line numberDiff line numberDiff line change
@@ -127,6 +127,7 @@ int TestCalculateDistanceBetweenPointAndLineString()
127127
{
128128
// Create an example Linestring
129129
lanelet::LineString2d linestring;
130+
130131
lanelet::Point2d p1(0, 1.0,
131132
0.0); // First argument is ID (set it to 0 for now)
132133
linestring.push_back(p1);
@@ -241,7 +242,7 @@ db_msgs::msg::LaneletsStamped GetTestRoadModelForRecenterTests()
241242
std::vector<db_msgs::msg::Lanelet> lanelet_vec(n_lanelets);
242243
message.lanelets = lanelet_vec;
243244

244-
// global position
245+
// Global position
245246
geometry_msgs::msg::PoseStamped msg_global_pose;
246247
msg_global_pose.header.frame_id = "base_link";
247248

@@ -267,7 +268,7 @@ db_msgs::msg::LaneletsStamped GetTestRoadModelForRecenterTests()
267268

268269
tf2::Quaternion quaternion;
269270

270-
// vehicle position in global cosy
271+
// Vehicle position in global cosy
271272
message.pose.position.x = 0.0;
272273
message.pose.position.y = 0.0;
273274
quaternion.setRPY(0, 0, 0);
@@ -276,7 +277,7 @@ db_msgs::msg::LaneletsStamped GetTestRoadModelForRecenterTests()
276277
message.pose.orientation.z = quaternion.getZ();
277278
message.pose.orientation.w = quaternion.getW();
278279

279-
// street layout in current local cosy = global cosy since vehicle position is
280+
// Street layout in current local cosy = global cosy since vehicle position is
280281
// at the origin in the global cosy
281282
message.lanelets[0].linestrings[0].points[0].pose.position.x = 0.0;
282283
message.lanelets[0].linestrings[0].points[0].pose.position.y = -0.5;
@@ -349,7 +350,7 @@ int TestRecenterGoalpoint()
349350
goal_point.y() = 0.25;
350351
goal_point_recentered = mission_planner.RecenterGoalPoint(goal_point, converted_lanelets);
351352

352-
// expect re-centered point to lie on y coordinate 0
353+
// Expect re-centered point to lie on y coordinate 0
353354
EXPECT_NEAR(goal_point_recentered.x(), goal_point.x(), 1e-5);
354355
EXPECT_NEAR(goal_point_recentered.y(), 0.0, 1e-5);
355356

@@ -359,7 +360,7 @@ int TestRecenterGoalpoint()
359360
goal_point.y() = -0.2;
360361
goal_point_recentered = mission_planner.RecenterGoalPoint(goal_point, converted_lanelets);
361362

362-
// expect re-centered point to lie on y coordinate 0 but with x coord equal to
363+
// Expect re-centered point to lie on y coordinate 0 but with x coord equal to
363364
// goal_point (removes lateral error/noise)
364365
EXPECT_NEAR(goal_point_recentered.x(), goal_point.x(), 1e-5);
365366
EXPECT_NEAR(goal_point_recentered.y(), 0.0, 1e-5);
@@ -371,7 +372,7 @@ int TestRecenterGoalpoint()
371372
goal_point.y() = 1.75;
372373
goal_point_recentered = mission_planner.RecenterGoalPoint(goal_point, converted_lanelets);
373374

374-
// expect re-centered point to lie on y coordinate 0 but with x coord equal to
375+
// Expect re-centered point to lie on y coordinate 0 but with x coord equal to
375376
// goal_point (removes lateral error/noise)
376377
EXPECT_NEAR(goal_point_recentered.x(), goal_point.x(), 1e-5);
377378
EXPECT_NEAR(goal_point_recentered.y(), 1.5, 1e-5);
@@ -416,7 +417,7 @@ int TestCheckIfGoalPointShouldBeReset()
416417
lanelet::BasicPoint2d point(-1.0, 0.0);
417418
MissionPlanner.goal_point(point);
418419

419-
// set a non-default mission to make the goal point reset work
420+
// Set a non-default mission to make the goal point reset work
420421
autoware_planning_msgs::msg::Mission mission_msg;
421422
mission_msg.mission_type = autoware_planning_msgs::msg::Mission::LANE_CHANGE_LEFT;
422423
MissionPlanner.CallbackMissionMessages_(mission_msg);
@@ -433,7 +434,7 @@ int TestCheckIfGoalPointShouldBeReset()
433434
// TEST 2: check if goal point reset is skipped in default mission
434435
MissionPlanner.goal_point(point);
435436

436-
// set a non-default mission to make the goal point reset work
437+
// Set a non-default mission to make the goal point reset work
437438
mission_msg.mission_type = autoware_planning_msgs::msg::Mission::LANE_KEEP;
438439
MissionPlanner.CallbackMissionMessages_(mission_msg);
439440

‎planning/mapless_architecture/autoware_local_mission_planner_common/include/autoware/local_mission_planner_common/helper_functions.hpp

+19-24
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ class Pose2D
3030
Pose2D();
3131
Pose2D(const double x, const double y, const double psi = 0.0);
3232

33-
// accessors and mutators
33+
// Accessors and mutators
3434
double get_x() const;
3535
double get_y() const;
3636
Eigen::Vector2d get_xy() const;
@@ -43,7 +43,7 @@ class Pose2D
4343
void set_psi(const double psi);
4444

4545
private:
46-
// data variables
46+
// Data variables
4747
Eigen::Vector2d xy_;
4848
double psi_;
4949
};
@@ -57,9 +57,9 @@ class Pose2D
5757
* providing the absolute pose of the new cosy as "pose_prev" and the
5858
* absolute pose of the old/current cosy as "cosy_rel".
5959
*
60-
* @param cosy_rel translation and rotation between the current/old cosy and
60+
* @param cosy_rel Translation and rotation between the current/old cosy and
6161
* a new/go-to cosy
62-
* @param pose_prev coordinates and heading of a pose in the current/old cosy
62+
* @param pose_prev Coordinates and heading of a pose in the current/old cosy
6363
* @return Pose coordinates and heading of pose_prev in the new cosy
6464
* (defined by the shift cosy_rel between previous and current cosy)
6565
*/
@@ -148,7 +148,7 @@ std::vector<std::vector<int>> GetAllSuccessorSequences(
148148
* @param id_initial_lanelet ID of lanelet from where neighbor search is
149149
started
150150
* @param adjacent_lane_type Specifies whether predecessors or successors
151-
should be targeted (e.g. lanelet_tools::AdjacentLaneType::kPredecessors)
151+
should be targeted (e.g. lanelet_tools::AdjacentLaneType::kPredecessors)
152152
*
153153
* @return Collection of sequences of all adjacent lanelets
154154
*/
@@ -157,18 +157,16 @@ std::vector<std::vector<int>> GetAllLaneletSequences(
157157
const AdjacentLaneType adjacent_lane_type);
158158

159159
/**
160-
* @brief Find relevant adjacent (successors or predecessors) lanelets
161-
(currently relevant means leading towards goal) among a set of
162-
provided adjacent lanelets (ids_adjacent_lanelets)
160+
* @brief Find relevant adjacent (successors or predecessors) lanelets (currently relevant means
161+
leading towards goal) among a set of provided adjacent lanelets (ids_adjacent_lanelets)
163162
*
164163
* @param lanelet_connections Relation between individual lanelets
165164
(successors/neighbors)
166165
* @param ids_adjacent_lanelets IDs of all available adjacent lanelets
167166
(either successors or predecessors)
168167
* @param do_include_navigation_info Whether to use navigation info to
169-
* determine relevant successors (true) or not (false); if
170-
navigation info is not used, the ID of the first direct successors will be
171-
returned
168+
* determine relevant successors (true) or not (false); if navigation info is not used,
169+
the ID of the first direct successors will be returned
172170
* @return ID of relevant successor lanelet
173171
*/
174172
std::vector<int> GetRelevantAdjacentLanelets(
@@ -179,11 +177,10 @@ std::vector<int> GetRelevantAdjacentLanelets(
179177
* @brief Get a complete lanelet ID sequence starting from an initial lanelet.
180178
*
181179
* @param lanelet_id_sequence_current Current lanelet ID sequence (of
182-
* previous iteration); this is the start for the search in the current
183-
* iteration
180+
* previous iteration); this is the start for the search in the current iteration
184181
* @param lanelets_already_visited List of already visited lanelet IDs
185-
* @param ids_relevant_lanelets IDs of the relevant adjacent
186-
* (successor or predecessor) lanelets
182+
* @param ids_relevant_lanelets IDs of the relevant adjacent (successor or predecessor)
183+
* lanelets
187184
* @param id_initial_lanelet ID of lanelet from which search was
188185
* started initially
189186
* @return - Vector containing IDs of a completed lanelet sequence; is empty
@@ -197,7 +194,7 @@ std::tuple<std::vector<int>, bool> GetCompletedLaneletSequence(
197194
const std::vector<int> ids_relevant_lanelets, const int id_initial_lanelet);
198195

199196
/**
200-
* @brief The vehicle side.
197+
* @brief The vehicle side (left or right).
201198
*
202199
*/
203200
enum VehicleSide { kLeft = 0, kRight = 1 };
@@ -231,15 +228,13 @@ std::vector<int> GetAllNeighboringLaneletIDs(
231228
* determine relevant neighbors (true) or
232229
* not (false)
233230
* @param recursiveness (defaults to 1)
234-
* level of recursiveness for neighbor search
235-
* - recursivenes=-1 means that the most outside lanes are requested
236-
(returns initial lanelet ID if no neighbors are available -> initial lanelet
237-
is the most outside lane)
238-
* - recursiveness>=0 means that the direct neighbors (1), neighbors of
239-
neighbors (2), ..., are searched (returns -1 if no lanelet is
240-
available at the specified level of recursiveness)
231+
* - level of recursiveness for neighbor search
232+
* - recursivenes=-1 means that the most outside lanes are requested (returns initial lanelet ID
233+
if no neighbors are available -> initial lanelet is the most outside lane)
234+
* - recursiveness>=0 means that the direct neighbors (1), neighbors of neighbors (2), ..., are
235+
searched (returns -1 if no lanelet is available at the specified level of recursiveness)
241236
*
242-
* @return ID of neighboring lanelet (returns -1 if no neighbor available)
237+
* @return ID of neighboring lanelet (returns -1 if no neighbor available)
243238
*/
244239
int GetNeighboringLaneletID(
245240
const std::vector<LaneletConnection> & lanelet_connections, const int id_initial_lanelet,

‎planning/mapless_architecture/autoware_local_mission_planner_common/src/helper_functions.cpp

+54-46
Original file line numberDiff line numberDiff line change
@@ -13,10 +13,10 @@ namespace autoware::mapless_architecture
1313

1414
double NormalizePsi(const double psi)
1515
{
16-
// remove multiples of 2 PI by using modulo on absolute value and apply sign
16+
// Remove multiples of 2 PI by using modulo on absolute value and apply sign
1717
double psi_out = copysign(fmod(fabs(psi), M_PI * 2.0), psi);
1818

19-
// restrict psi to [-pi, pi[
19+
// Restrict psi to [-pi, pi[
2020
if (psi_out >= M_PI)
2121
psi_out -= 2.0 * M_PI;
2222
else if (psi_out < -M_PI)
@@ -30,22 +30,22 @@ std::vector<double> GetPsiForPoints(const std::vector<geometry_msgs::msg::Point>
3030
int num_points = points.size();
3131
std::vector<double> tang_vecs(num_points * 2);
3232

33-
// get heading vector for first point
33+
// Get heading vector for first point
3434
tang_vecs[0] = points[1].x - points[0].x;
3535
tang_vecs[1] = points[1].y - points[0].y;
3636

37-
// use one point before and after the targeted one for heading vector (more
37+
// Use one point before and after the targeted one for heading vector (more
3838
// stable/robust than relying on a single pair of points)
3939
for (int i = 1; i < num_points - 1; i++) {
4040
tang_vecs[2 * i] = points[i + 1].x - points[i - 1].x;
4141
tang_vecs[2 * i + 1] = points[i + 1].y - points[i - 1].y;
4242
}
4343

44-
// get heading vector for last point
44+
// Get heading vector for last point
4545
tang_vecs[2 * (num_points - 1)] = points[num_points - 1].x - points[num_points - 2].x;
4646
tang_vecs[2 * (num_points - 1) + 1] = points[num_points - 1].y - points[num_points - 2].y;
4747

48-
// calculate heading angles with atan2
48+
// Calculate heading angles with atan2
4949
std::vector<double> psi_points(num_points);
5050
for (int i = 0; i < num_points; i++) {
5151
psi_points[i] = NormalizePsi(std::atan2(tang_vecs[2 * i + 1], tang_vecs[2 * i]));
@@ -59,50 +59,61 @@ Pose2D::Pose2D()
5959
this->set_xy(0.0, 0.0);
6060
this->set_psi(0.0);
6161
}
62+
6263
Pose2D::Pose2D(const double x, const double y, const double psi /* = 0.0 */)
6364
{
6465
this->set_xy(x, y);
6566
this->set_psi(psi);
6667
}
68+
6769
double Pose2D::get_x() const
6870
{
6971
return this->xy_(0);
7072
}
73+
7174
double Pose2D::get_y() const
7275
{
7376
return this->xy_(1);
7477
}
78+
7579
Eigen::Vector2d Pose2D::get_xy() const
7680
{
7781
return this->xy_;
7882
}
83+
7984
double Pose2D::get_psi() const
8085
{
8186
return this->psi_;
8287
}
88+
8389
geometry_msgs::msg::Point Pose2D::get_point() const
8490
{
8591
geometry_msgs::msg::Point tmp_point;
8692
tmp_point.x = this->xy_(0);
8793
tmp_point.y = this->xy_(1);
8894
return tmp_point;
8995
}
96+
9097
void Pose2D::set_x(const double x)
9198
{
9299
this->xy_(0) = x;
93100
}
101+
94102
void Pose2D::set_y(const double y)
95103
{
96104
this->xy_(1) = y;
97105
}
106+
98107
void Pose2D::set_xy(const double x, const double y)
99108
{
100109
this->xy_ = {x, y};
101110
}
111+
102112
void Pose2D::set_xy(const Eigen::Vector2d xy)
103113
{
104114
this->xy_ = xy;
105115
}
116+
106117
void Pose2D::set_psi(const double psi)
107118
{
108119
this->psi_ = psi;
@@ -189,15 +200,15 @@ std::vector<std::vector<int>> GetAllLaneletSequences(
189200
const std::vector<LaneletConnection> & lanelet_connections, const int id_initial_lanelet,
190201
const AdjacentLaneType adjacent_lane_type)
191202
{
192-
// initialize helper variables
203+
// Initialize helper variables
193204
bool do_include_navigation_info = false;
194205

195206
std::vector<int> lanelets_already_visited;
196207
std::vector<int> lanelet_id_sequence_temp{id_initial_lanelet};
197208

198209
std::vector<std::vector<int>> lanelet_sequences;
199210

200-
// loop as long as all successors of the initial lanelet have been searched
211+
// Loop as long as all successors of the initial lanelet have been searched
201212
// maximum iteration depth is (number_of_lanelets - 1) * 2
202213
for (size_t i = 0; i < lanelet_connections.size() * 2; i++) {
203214
// IDs which are relevant for searching adjacent lanelets (either successors
@@ -221,7 +232,7 @@ std::vector<std::vector<int>> GetAllLaneletSequences(
221232

222233
if (do_exit_outer_for_loop) break;
223234

224-
// store returned complete lanelet id sequence
235+
// Store returned complete lanelet id sequence
225236
if (!lanelet_id_sequence_completed.empty()) {
226237
lanelet_sequences.push_back(lanelet_id_sequence_completed);
227238
}
@@ -235,19 +246,19 @@ std::vector<int> GetRelevantAdjacentLanelets(
235246
{
236247
std::vector<int> ids_relevant_successors;
237248

238-
// return all successors if navigation info is not relevant
249+
// Return all successors if navigation info is not relevant
239250
if (do_include_navigation_info) {
240-
// loop through all successors and check if they lead towards the navigation
251+
// Loop through all successors and check if they lead towards the navigation
241252
// goal
242253
if (ids_adjacent_lanelets.front() >= 0) {
243254
for (std::size_t i = 0; i < ids_adjacent_lanelets.size(); i++) {
244-
// check if successor leads to goal
255+
// Check if successor leads to goal
245256
if (lanelet_connections[ids_adjacent_lanelets[i]].goal_information) {
246257
ids_relevant_successors.push_back(ids_adjacent_lanelets[i]);
247258
}
248259
}
249260
}
250-
// default return: valid successor lanelet not available
261+
// Default return: valid successor lanelet not available
251262
if (ids_relevant_successors.empty()) {
252263
ids_relevant_successors.push_back(-1);
253264
}
@@ -256,9 +267,7 @@ std::vector<int> GetRelevantAdjacentLanelets(
256267
}
257268

258269
// FIXME: avoid that list is empty -> has to be -1 if no relevant lanelet
259-
// exists
260-
// this fixes an issue that originates in the lanelet converter; should be
261-
// fixed there!
270+
// exists, this fixes an issue that originates in the lanelet converter; should be fixed there!
262271
if (ids_relevant_successors.empty()) {
263272
ids_relevant_successors.push_back(-1);
264273
}
@@ -273,47 +282,47 @@ std::tuple<std::vector<int>, bool> GetCompletedLaneletSequence(
273282
std::vector<int> lanelet_id_sequence_completed;
274283
bool do_exit_outer_for_loop = false;
275284

276-
// check if an adjacent lanelet is even available
285+
// Check if an adjacent lanelet is even available
277286
if (ids_relevant_lanelets.front() >= 0) {
278287
bool has_relevant_successor = false;
279288

280-
// loop though all relevant adjacent IDs and check whether or not they
289+
// Loop though all relevant adjacent IDs and check whether or not they
281290
// have already been visited
282291
for (const int & successor_id : ids_relevant_lanelets) {
283292
if (
284293
std::find(lanelets_already_visited.begin(), lanelets_already_visited.end(), successor_id) ==
285294
lanelets_already_visited.end()) {
286-
// add new ID to already visited vector
295+
// Add new ID to already visited vector
287296
lanelets_already_visited.push_back(successor_id);
288-
// add currently visited ID to temporary adjacent lanelet sequence
297+
// Add currently visited ID to temporary adjacent lanelet sequence
289298
lanelet_id_sequence_current.push_back(successor_id);
290299
has_relevant_successor = true;
291300
break;
292301
}
293302
}
294303

295-
// if all available adjacent lanelets were already visited, go back to
304+
// If all available adjacent lanelets were already visited, go back to
296305
// parent lanelet or exit loop
297306
if (!has_relevant_successor) {
298-
// pop parent lanelet except it is already the initial lanelet
307+
// Pop parent lanelet except it is already the initial lanelet
299308
if (lanelet_id_sequence_current.back() != id_initial_lanelet) {
300309
lanelet_id_sequence_current.pop_back();
301310
} else {
302-
// exit loop if initial lanelet has no relevant adjacent lanelets left
311+
// Exit loop if initial lanelet has no relevant adjacent lanelets left
303312
do_exit_outer_for_loop = true;
304313
}
305314
}
306315

307316
} else {
308-
// exit loop if initial lanelet has already no relevant adjacent lanelets
317+
// Exit loop if initial lanelet has already no relevant adjacent lanelets
309318
if (lanelet_id_sequence_current.back() == id_initial_lanelet) {
310319
do_exit_outer_for_loop = true;
311320
} else {
312-
// store lanelet sequence when it is completed (no unvisited adjacent
321+
// Store lanelet sequence when it is completed (no unvisited adjacent
313322
// lanelets left from current lanelet)
314323
lanelet_id_sequence_completed = lanelet_id_sequence_current;
315324

316-
// go back to parent lanelet ID and continue search from there
325+
// Go back to parent lanelet ID and continue search from there
317326
lanelet_id_sequence_current.pop_back();
318327
}
319328
}
@@ -327,24 +336,23 @@ std::vector<int> GetAllNeighboringLaneletIDs(
327336
int id_current_lanelet = id_initial_lanelet;
328337
std::vector<int> lanelet_id_neighbors;
329338

330-
// this function is only intended to return all neighboring lanelets, not only
339+
// This function is only intended to return all neighboring lanelets, not only
331340
// the ones leading towards goal. Therefore, this flag is set false for the
332341
// sub-function.
333342
const bool do_include_navigation_info = false;
334343

335-
// loop as long as all left or right neighbors of the initial lanelet have
336-
// been searched
337-
// maximum iteration depth is: number_of_lanelets
344+
// Loop as long as all left or right neighbors of the initial lanelet have
345+
// been searched, maximum iteration depth is: number_of_lanelets
338346
for (size_t i = 0; i < lanelet_connections.size(); i++) {
339347
int idx_tmp = GetNeighboringLaneletID(
340348
lanelet_connections, id_current_lanelet, side, do_include_navigation_info);
341349

342-
// if ID >= 0, continue search, else break
350+
// If ID >= 0, continue search, else break
343351
if (idx_tmp >= 0) {
344352
id_current_lanelet = idx_tmp;
345353
lanelet_id_neighbors.push_back(id_current_lanelet);
346354
} else {
347-
// if return vector is still empty because no neighbors are available,
355+
// If return vector is still empty because no neighbors are available,
348356
// return -1
349357
if (lanelet_id_neighbors.empty()) {
350358
lanelet_id_neighbors.push_back(-1);
@@ -360,45 +368,45 @@ int GetNeighboringLaneletID(
360368
const std::vector<LaneletConnection> & lanelet_connections, const int id_initial_lanelet,
361369
const VehicleSide side, const bool do_include_navigation_info, const int recursiveness)
362370
{
363-
// set default return id if initial lane has already no neighbors
371+
// Set default return id if initial lane has already no neighbors
364372
int id_neighbor_lanelet = -1;
365373

366-
// check if most outside lane is searched
367-
// here: return current lanelet's ID when no neighbors are available
374+
// Check if most outside lane is searched
375+
// Here: return current lanelet's ID when no neighbors are available
368376
if (recursiveness == -1) {
369377
id_neighbor_lanelet = id_initial_lanelet;
370378
}
371379

372-
// get ID of current lanelet's neighboring lanelet
380+
// Get ID of current lanelet's neighboring lanelet
373381
int id_neighbor_lanelet_tmp = lanelet_connections[id_initial_lanelet].neighbor_lanelet_ids[side];
374382

375-
// init counter to track current level of recursiveness in loop
383+
// Init counter to track current level of recursiveness in loop
376384
int recursiveness_counter = 0;
377385

378-
// loop as long as all neighbors of the initial lanelet have been searched
379-
// maximum iteration depth: number_of_lanelets
386+
// Loop as long as all neighbors of the initial lanelet have been searched, maximum iteration
387+
// depth: number_of_lanelets
380388
for (size_t i = 0; i < lanelet_connections.size(); i++) {
381-
// break while loop if desired recursiveness is reached
389+
// Break while loop if desired recursiveness is reached
382390
if (recursiveness != -1 && recursiveness_counter >= recursiveness) break;
383391

384-
// check if neighbor is available
392+
// Check if neighbor is available
385393
if (id_neighbor_lanelet_tmp >= 0) {
386-
// break if navigation info is considered AND the lanelet does not lead
394+
// Break if navigation info is considered AND the lanelet does not lead
387395
// towards goal
388396
if (
389397
do_include_navigation_info &&
390398
!lanelet_connections[id_neighbor_lanelet_tmp].goal_information) {
391399
break;
392400
}
393401

394-
// store current neighbor lanelet ID
402+
// Store current neighbor lanelet ID
395403
id_neighbor_lanelet = id_neighbor_lanelet_tmp;
396-
// query neighbor of neighbor and use as new start lanelet
404+
// Query neighbor of neighbor and use as new start lanelet
397405
id_neighbor_lanelet_tmp =
398406
lanelet_connections[id_neighbor_lanelet_tmp].neighbor_lanelet_ids[side];
399407

400408
} else {
401-
// return -1 if lanelet ID at specific recursiveness is requested
409+
// Return -1 if lanelet ID at specific recursiveness is requested
402410
if (recursiveness >= 0) {
403411
id_neighbor_lanelet = -1;
404412
}
@@ -422,7 +430,7 @@ int FindOccupiedLaneletID(
422430
{
423431
int id_occupied_lanelet = -1;
424432

425-
// check if position is within one of the available lanelet
433+
// Check if position is within one of the available lanelet
426434
for (size_t i = 0; i < lanelets.size(); i++) {
427435
if (lanelet::geometry::inside(lanelets[i], position)) {
428436
id_occupied_lanelet = i;

‎planning/mapless_architecture/autoware_local_road_provider/include/autoware/local_road_provider/local_road_provider_node.hpp

-7
Original file line numberDiff line numberDiff line change
@@ -26,20 +26,13 @@ class LocalRoadProviderNode : public rclcpp::Node
2626
LocalRoadProviderNode();
2727

2828
private:
29-
// ###########################################################################
30-
// # PRIVATE PROCESSING METHODS
31-
// ###########################################################################
32-
3329
/**
3430
* @brief The callback for the LaneletsStamped messages.
3531
*
3632
* @param msg The db_msgs::msg::LaneletsStamped message.
3733
*/
3834
void CallbackLaneletsMessages_(const db_msgs::msg::LaneletsStamped & msg);
3935

40-
// ###########################################################################
41-
// # PRIVATE VARIABLES
42-
// ###########################################################################
4336
// Declare ROS2 publisher and subscriber
4437

4538
rclcpp::Publisher<autoware_planning_msgs::msg::RoadSegments>::SharedPtr road_publisher_;

‎planning/mapless_architecture/autoware_mission_lane_converter/include/autoware/mission_lane_converter/mission_lane_converter_node.hpp

+32-19
Original file line numberDiff line numberDiff line change
@@ -27,30 +27,21 @@ class MissionLaneConverterNode : public rclcpp::Node
2727
public:
2828
MissionLaneConverterNode();
2929

30-
// ###########################################################################
31-
// # PUBLIC METHODS
32-
// ###########################################################################
33-
3430
/**
3531
* @brief Converts the mission message into a reference trajectory which is
3632
* forwarded to a local trajectory planner for refinement.
3733
*
3834
* @param msg The mission lanes
3935
* @return std::tuple<autoware_auto_planning_msgs::msg::Trajectory,
40-
visualization_msgs::msg::Marker,
41-
autoware_auto_planning_msgs::msg::Path,
42-
visualization_msgs::msg::Marker>
36+
* visualization_msgs::msg::Marker, autoware_auto_planning_msgs::msg::Path,
37+
* visualization_msgs::msg::Marker>
4338
*/
4439
std::tuple<
4540
autoware_auto_planning_msgs::msg::Trajectory, visualization_msgs::msg::Marker,
4641
autoware_auto_planning_msgs::msg::Path, visualization_msgs::msg::MarkerArray>
4742
ConvertMissionToTrajectory(const autoware_planning_msgs::msg::MissionLanesStamped & msg);
4843

4944
private:
50-
// ###########################################################################
51-
// # PRIVATE PROCESSING METHODS
52-
// ###########################################################################
53-
5445
/**
5546
* @brief Computes a trajectory based on the mission planner input.
5647
*
@@ -99,14 +90,39 @@ class MissionLaneConverterNode : public rclcpp::Node
9990
*/
10091
void TimedStartupTrajectoryCallback();
10192

93+
/**
94+
*@brief Create a path bound.
95+
*
96+
*@param bound_path The path.
97+
*@param path_vis The visualization marker.
98+
*@param bound_mission_lane The mission lane.
99+
*@param id_marker The ID marker.
100+
*/
102101
void CreatePathBound_(
103102
std::vector<geometry_msgs::msg::Point> & bound_path, visualization_msgs::msg::Marker & path_vis,
104103
const std::vector<geometry_msgs::msg::Point> & bound_mission_lane, const int id_marker);
105104

105+
/**
106+
*@brief Add a path point.
107+
*
108+
*@param pth_msg The path.
109+
*@param x The x value.
110+
*@param y The y value.
111+
*@param v_x The v_x value.
112+
*/
106113
void AddPathPoint_(
107114
autoware_auto_planning_msgs::msg::Path & pth_msg, const double x, const double y,
108115
const double v_x);
109116

117+
/**
118+
*@brief Create a motion planner input.
119+
*
120+
*@param trj_msg The trajectory.
121+
*@param path_msg The path.
122+
*@param trj_vis The visualization marker for the trajectory.
123+
*@param path_vis The visualization marker for the path.
124+
*@param centerline_mission_lane The centerline of the mission lane.
125+
*/
110126
void CreateMotionPlannerInput_(
111127
autoware_auto_planning_msgs::msg::Trajectory & trj_msg,
112128
autoware_auto_planning_msgs::msg::Path & path_msg, visualization_msgs::msg::Marker & trj_vis,
@@ -140,9 +156,6 @@ class MissionLaneConverterNode : public rclcpp::Node
140156
visualization_msgs::msg::Marker GetGlobalTrjVisualization_(
141157
const autoware_auto_planning_msgs::msg::Trajectory & trj_msg);
142158

143-
// ###########################################################################
144-
// # PRIVATE VARIABLES
145-
// ###########################################################################
146159
// Declare ROS2 publisher and subscriber
147160

148161
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_subscriber_;
@@ -165,17 +178,17 @@ class MissionLaneConverterNode : public rclcpp::Node
165178

166179
rclcpp::TimerBase::SharedPtr timer_;
167180

168-
// switch to print a warning about wrongly configured odometry frames
181+
// Switch to print a warning about wrongly configured odometry frames
169182
bool b_global_odometry_deprecation_warning_ = false;
170183
bool received_motion_update_once_ = false;
171-
// store initial and last available odom messages
184+
185+
// Store initial and last available odom messages
172186
nav_msgs::msg::Odometry last_odom_msg_, initial_odom_msg_;
173187

174-
// workaround to start the vehicle driving into the computed local road
175-
// model
188+
// Workaround to start the vehicle driving into the computed local road model
176189
bool mission_lanes_available_once_ = false;
177190

178-
// ros parameters
191+
// ROS parameters
179192
float target_speed_;
180193
};
181194
} // namespace autoware::mapless_architecture

‎planning/mapless_architecture/autoware_mission_lane_converter/src/mission_lane_converter_node.cpp

+77-80
Large diffs are not rendered by default.

‎planning/mapless_architecture/autoware_mission_lane_converter/test/include/test_mission_planner_converter.hpp

+6-1
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,13 @@
77
namespace autoware::mapless_architecture
88
{
99

10+
/**
11+
* @brief Test the ConvertMissionToTrajectory() function.
12+
*
13+
* @return int: returns 0 on success
14+
*/
1015
int TestMissionToTrajectory();
1116

12-
}
17+
} // namespace autoware::mapless_architecture
1318

1419
#endif // TEST_MISSION_PLANNER_CONVERTER_HPP_

‎planning/mapless_architecture/autoware_mission_lane_converter/test/src/test_mission_planner_converter.cpp

+13-13
Original file line numberDiff line numberDiff line change
@@ -15,24 +15,24 @@ int TestMissionToTrajectory()
1515

1616
autoware_planning_msgs::msg::MissionLanesStamped mission_msg;
1717

18-
// set target lane to ego lane
18+
// Set target lane to ego lane
1919
mission_msg.target_lane = 0;
2020

21-
// add a driving corridor to the ego lane
21+
// Add a driving corridor to the ego lane
2222
mission_msg.ego_lane = autoware_planning_msgs::msg::DrivingCorridor();
2323

24-
// add points to the ego lane centerline
24+
// Add points to the ego lane centerline
2525
mission_msg.ego_lane.centerline.push_back(geometry_msgs::msg::Point());
2626
mission_msg.ego_lane.centerline.back().x = 0.0;
2727
mission_msg.ego_lane.centerline.back().y = 0.0;
2828

29-
// get converted trajectory
29+
// Get converted trajectory
3030
std::tuple<
3131
autoware_auto_planning_msgs::msg::Trajectory, visualization_msgs::msg::Marker,
3232
autoware_auto_planning_msgs::msg::Path, visualization_msgs::msg::MarkerArray>
3333
mission_to_trj = mission_converter.ConvertMissionToTrajectory(mission_msg);
3434

35-
// extract trajectory
35+
// Extract trajectory
3636
autoware_auto_planning_msgs::msg::Trajectory trj_msg = std::get<0>(mission_to_trj);
3737

3838
EXPECT_EQ(trj_msg.points.back().pose.position.x, mission_msg.ego_lane.centerline.back().x);
@@ -51,10 +51,10 @@ int TestMissionToTrajectory()
5151
mission_msg.ego_lane.centerline.back().x = 2.0;
5252
mission_msg.ego_lane.centerline.back().y = 2.0;
5353

54-
// convert
54+
// Convert
5555
mission_to_trj = mission_converter.ConvertMissionToTrajectory(mission_msg);
5656

57-
// extract trajectory
57+
// Extract trajectory
5858
trj_msg = std::get<0>(mission_to_trj);
5959

6060
EXPECT_EQ(trj_msg.points.back().pose.position.x, mission_msg.ego_lane.centerline.back().x);
@@ -69,13 +69,13 @@ int TestMissionToTrajectory()
6969
mission_msg.drivable_lanes_left.back().centerline.back().x = 5.0;
7070
mission_msg.drivable_lanes_left.back().centerline.back().y = 3.0;
7171

72-
// set target lane to neighbor left
72+
// Set target lane to neighbor left
7373
mission_msg.target_lane = -1;
7474

75-
// convert
75+
// Convert
7676
mission_to_trj = mission_converter.ConvertMissionToTrajectory(mission_msg);
7777

78-
// extract trajectory
78+
// Extract trajectory
7979
trj_msg = std::get<0>(mission_to_trj);
8080

8181
EXPECT_EQ(
@@ -94,13 +94,13 @@ int TestMissionToTrajectory()
9494
mission_msg.drivable_lanes_right.back().centerline.back().x = 3.0;
9595
mission_msg.drivable_lanes_right.back().centerline.back().y = 3.6;
9696

97-
// set target lane to neighbor right
97+
// Set target lane to neighbor right
9898
mission_msg.target_lane = 1;
9999

100-
// convert
100+
// Convert
101101
mission_to_trj = mission_converter.ConvertMissionToTrajectory(mission_msg);
102102

103-
// extract trajectory
103+
// Extract trajectory
104104
trj_msg = std::get<0>(mission_to_trj);
105105

106106
EXPECT_EQ(

0 commit comments

Comments
 (0)
Please sign in to comment.