17
17
#ifndef VECTOR_MAP_VECTOR_MAP_H
18
18
#define VECTOR_MAP_VECTOR_MAP_H
19
19
20
- #include < fstream>
21
20
#include < ros/ros.h>
22
21
#include < geometry_msgs/Point.h>
23
22
#include < geometry_msgs/Quaternion.h>
56
55
#include < vector_map_msgs/FenceArray.h>
57
56
#include < vector_map_msgs/RailCrossingArray.h>
58
57
58
+ #include < fstream>
59
+ #include < map>
60
+ #include < string>
61
+ #include < vector>
62
+
59
63
namespace vector_map
60
64
{
61
65
using vector_map_msgs::Point ;
@@ -124,7 +128,7 @@ using vector_map_msgs::WallArray;
124
128
using vector_map_msgs::FenceArray;
125
129
using vector_map_msgs::RailCrossingArray;
126
130
127
- using category_t = unsigned long long ;
131
+ using category_t = uint32_t ;
128
132
129
133
enum Category : category_t
130
134
{
@@ -297,7 +301,7 @@ std::vector<T> parse(const std::string& csv_file)
297
301
{
298
302
std::ifstream ifs (csv_file.c_str ());
299
303
std::string line;
300
- std::getline (ifs, line); // remove first line
304
+ std::getline (ifs, line); // remove first line
301
305
std::vector<T> objs;
302
306
while (std::getline (ifs, line))
303
307
{
@@ -309,42 +313,6 @@ std::vector<T> parse(const std::string& csv_file)
309
313
return objs;
310
314
}
311
315
312
- /* namespace */
313
- /* { */
314
- /* void updatePoint(std::map<Key<Point>, Point>& map, const PointArray& msg); */
315
- /* void updateVector(std::map<Key<Vector>, Vector>& map, const VectorArray& msg); */
316
- /* void updateLine(std::map<Key<Line>, Line>& map, const LineArray& msg); */
317
- /* void updateArea(std::map<Key<Area>, Area>& map, const AreaArray& msg); */
318
- /* void updatePole(std::map<Key<Pole>, Pole>& map, const PoleArray& msg); */
319
- /* void updateBox(std::map<Key<Box>, Box>& map, const BoxArray& msg); */
320
- /* void updateDTLane(std::map<Key<DTLane>, DTLane>& map, const DTLaneArray& msg); */
321
- /* void updateNode(std::map<Key<Node>, Node>& map, const NodeArray& msg); */
322
- /* void updateLane(std::map<Key<Lane>, Lane>& map, const LaneArray& msg); */
323
- /* void updateWayArea(std::map<Key<WayArea>, WayArea>& map, const WayAreaArray& msg); */
324
- /* void updateRoadEdge(std::map<Key<RoadEdge>, RoadEdge>& map, const RoadEdgeArray& msg); */
325
- /* void updateGutter(std::map<Key<Gutter>, Gutter>& map, const GutterArray& msg); */
326
- /* void updateCurb(std::map<Key<Curb>, Curb>& map, const CurbArray& msg); */
327
- /* void updateWhiteLine(std::map<Key<WhiteLine>, WhiteLine>& map, const WhiteLineArray& msg); */
328
- /* void updateStopLine(std::map<Key<StopLine>, StopLine>& map, const StopLineArray& msg); */
329
- /* void updateZebraZone(std::map<Key<ZebraZone>, ZebraZone>& map, const ZebraZoneArray& msg); */
330
- /* void updateCrossWalk(std::map<Key<CrossWalk>, CrossWalk>& map, const CrossWalkArray& msg); */
331
- /* void updateRoadMark(std::map<Key<RoadMark>, RoadMark>& map, const RoadMarkArray& msg); */
332
- /* void updateRoadPole(std::map<Key<RoadPole>, RoadPole>& map, const RoadPoleArray& msg); */
333
- /* void updateRoadSign(std::map<Key<RoadSign>, RoadSign>& map, const RoadSignArray& msg); */
334
- /* void updateSignal(std::map<Key<Signal>, Signal>& map, const SignalArray& msg); */
335
- /* void updateStreetLight(std::map<Key<StreetLight>, StreetLight>& map, const StreetLightArray& msg); */
336
- /* void updateUtilityPole(std::map<Key<UtilityPole>, UtilityPole>& map, const UtilityPoleArray& msg); */
337
- /* void updateGuardRail(std::map<Key<GuardRail>, GuardRail>& map, const GuardRailArray& msg); */
338
- /* void updateSideWalk(std::map<Key<SideWalk>, SideWalk>& map, const SideWalkArray& msg); */
339
- /* void updateDriveOnPortion(std::map<Key<DriveOnPortion>, DriveOnPortion>& map, const DriveOnPortionArray& msg); */
340
- /* void updateCrossRoad(std::map<Key<CrossRoad>, CrossRoad>& map, const CrossRoadArray& msg); */
341
- /* void updateSideStrip(std::map<Key<SideStrip>, SideStrip>& map, const SideStripArray& msg); */
342
- /* void updateCurveMirror(std::map<Key<CurveMirror>, CurveMirror>& map, const CurveMirrorArray& msg); */
343
- /* void updateWall(std::map<Key<Wall>, Wall>& map, const WallArray& msg); */
344
- /* void updateFence(std::map<Key<Fence>, Fence>& map, const FenceArray& msg); */
345
- /* void updateRailCrossing(std::map<Key<RailCrossing>, RailCrossing>& map, const RailCrossingArray& msg); */
346
- /* } // namespace */
347
-
348
316
class VectorMap
349
317
{
350
318
private:
@@ -530,7 +498,7 @@ geometry_msgs::Point convertPointToGeomPoint(const Point& point);
530
498
Point convertGeomPointToPoint (const geometry_msgs::Point & geom_point);
531
499
geometry_msgs::Quaternion convertVectorToGeomQuaternion (const Vector& vector);
532
500
Vector convertGeomQuaternionToVector (const geometry_msgs::Quaternion& geom_quaternion);
533
- } // namespace vector_map
501
+ } // namespace vector_map
534
502
535
503
std::ostream& operator <<(std::ostream& os, const vector_map::Point & obj);
536
504
std::ostream& operator <<(std::ostream& os, const vector_map::Vector& obj);
@@ -598,4 +566,4 @@ std::istream& operator>>(std::istream& is, vector_map::Wall& obj);
598
566
std::istream& operator >>(std::istream& is, vector_map::Fence& obj);
599
567
std::istream& operator >>(std::istream& is, vector_map::RailCrossing& obj);
600
568
601
- #endif // VECTOR_MAP_VECTOR_MAP_H
569
+ #endif // VECTOR_MAP_VECTOR_MAP_H
0 commit comments