Skip to content

Commit b117357

Browse files
committed
save
1 parent 2202deb commit b117357

File tree

7 files changed

+29
-7
lines changed

7 files changed

+29
-7
lines changed

common/op_planner/src/MappingHelpers.cpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -106,8 +106,11 @@ void MappingHelpers::ConstructRoadNetworkFromROSMessage(const std::vector<Utilit
106106
const std::vector<UtilityHNS::AisanCrossWalkFileReader::AisanCrossWalk>& crosswalk_data,
107107
const std::vector<UtilityHNS::AisanNodesFileReader::AisanNode>& nodes_data,
108108
const std::vector<UtilityHNS::AisanDataConnFileReader::DataConn>& conn_data,
109-
const GPSPoint& origin, RoadNetwork& map, const bool& bSpecialFlag,
110-
const bool& bFindLaneChangeLanes, const bool& bFindCurbsAndWayArea)
109+
const GPSPoint& origin,
110+
RoadNetwork& map,
111+
const bool& bSpecialFlag,
112+
const bool& bFindLaneChangeLanes,
113+
const bool& bFindCurbsAndWayArea)
111114
{
112115
vector<Lane> roadLanes;
113116
Lane lane_obj;

core_planning/lane_planner/lib/lane_planner/lane_planner_vmap.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -238,6 +238,7 @@ vector_map::Point find_nearest_point(const VectorMap& vmap, const vector_map::Po
238238

239239
double distance = DBL_MAX;
240240
for (const vector_map::Point& p : vmap.points) {
241+
//reference: https://cplusplus.com/reference/cmath/hypot/
241242
double d = hypot(p.bx - point.bx, p.ly - point.ly);
242243
if (d <= distance) {
243244
nearest_point = p;
@@ -590,6 +591,7 @@ VectorMap create_coarse_vmap_from_route(const tablet_socket_msgs::route_cmd& rou
590591

591592
VectorMap create_fine_vmap(const VectorMap& lane_vmap, int lno, const VectorMap& coarse_vmap, double search_radius,
592593
int waypoint_max)
594+
//fine 精细 coarse 粗
593595
{
594596
VectorMap fine_vmap;
595597
VectorMap null_vmap;

core_planning/op_global_planner/include/op_global_planner_core.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ class WayPlannerParams
7575

7676
WayPlannerParams()
7777
{
78-
bEnableDynamicMapUpdate = false;
78+
bEnableDynamicMapUpdate = false;
7979
bEnableReplanning = false;
8080
bEnableHMI = false;
8181
bEnableSmoothing = false;

core_planning/op_global_planner/nodes/op_global_planner_core.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -400,6 +400,7 @@ void GlobalPlanner::MainLoop()
400400
{
401401
ros::Rate loop_rate(25);
402402
timespec animation_timer;
403+
// GetTickCount 具体作用是啥?
403404
UtilityHNS::UtilityH::GetTickCount(animation_timer);
404405

405406
while (ros::ok())
@@ -427,7 +428,7 @@ void GlobalPlanner::MainLoop()
427428
else if (m_params.mapSource == PlannerHNS::MAP_AUTOWARE && !m_bKmlMap)
428429
{
429430
std::vector<UtilityHNS::AisanDataConnFileReader::DataConn> conn_data;;
430-
431+
//根据地图是否有节点(Node):有节点:m_MapRaw.GetVersion()==2,无节点:m_MapRaw.GetVersion()==1
431432
if(m_MapRaw.GetVersion()==2)
432433
{
433434
std::cout << "Map Version 2" << endl;

core_planning/way_planner/include/way_planner_core.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,7 @@ class AutowareRoadNetwork
9797
}
9898
};
9999

100-
enum MAP_SOURCE_TYPE{MAP_AUTOWARE, MAP_FOLDER, MAP_KML_FILE};
100+
enum MAP_SOURCE_TYPE{MAP_AUTOWARE, MAP_FOLDER, MAP_KML_FILE}; //这几个枚举定义的是什么类型,没有整明白
101101

102102
class WayPlannerParams
103103
{

core_planning/waypoint_maker/nodes/waypoint_extractor/waypoint_extractor.cpp

+11
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,17 @@ class WaypointExtractor
5252
std::string directory_path, filename, extension;
5353

5454
tmp = file_path;
55+
/*
56+
reference
57+
关于 std::string::size_type
58+
https://ask.csdn.net/questions/7418788
59+
*/
60+
61+
/*
62+
reference
63+
关于 find_last_of
64+
https://blog.csdn.net/zhangxiao93/article/details/54381613/
65+
*/
5566
const std::string::size_type idx_slash(tmp.find_last_of("/"));
5667
if (idx_slash != std::string::npos)
5768
{

core_planning/waypoint_maker/nodes/waypoint_loader/waypoint_loader_core.cpp

+7-2
Original file line numberDiff line numberDiff line change
@@ -225,7 +225,8 @@ FileFormat WaypointLoaderNode::checkFileFormat(const char* filename)
225225
// parse first line
226226
std::vector<std::string> parsed_columns;
227227
parseColumns(line, &parsed_columns);
228-
228+
//关于 isdigit
229+
//https://blog.csdn.net/Guo___Liang/article/details/121981604
229230
// check if first element in the first column does not include digit
230231
if (!std::any_of(parsed_columns.at(0).cbegin(), parsed_columns.at(0).cend(), isdigit))
231232
{
@@ -288,6 +289,10 @@ void parseColumns(const std::string& line, std::vector<std::string>* columns)
288289
{
289290
while (1)
290291
{
292+
/*
293+
主要功能:删除字符串中多余的空格
294+
然后将字符串填充到相应的容器中
295+
*/
291296
auto res = std::find(column.begin(), column.end(), ' ');
292297
// 查找是否存在空格,查找成功则返回一个指向指定元素的迭代器
293298
// reference: https://blog.csdn.net/qq_43799400/article/details/122699509
@@ -306,7 +311,7 @@ void parseColumns(const std::string& line, std::vector<std::string>* columns)
306311
columns->emplace_back(column);
307312
// note by xz 20220810
308313
//不为空,将字符串装载到容器 columns 里面
309-
// reference:
314+
// reference: https://blog.csdn.net/weixin_45880571/article/details/119450328
310315
}
311316
}
312317
}

0 commit comments

Comments
 (0)