Skip to content

Commit 94fd856

Browse files
Work on documentation
1 parent a7a9a94 commit 94fd856

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,

0 commit comments

Comments
 (0)