Skip to content

Commit 1fa3767

Browse files
Joshua WhitleyGeoffrey Biggs
Joshua Whitley
authored and
Geoffrey Biggs
committed
Adding roslint to vector_map and applying suggestions.
1 parent df8f9fa commit 1fa3767

File tree

4 files changed

+29
-48
lines changed

4 files changed

+29
-48
lines changed

vector_map/CMakeLists.txt

+9-1
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@ find_package(autoware_build_flags REQUIRED)
66
find_package(catkin REQUIRED COMPONENTS
77
tf
88
geometry_msgs
9+
roslint
910
vector_map_msgs
1011
visualization_msgs
1112
)
@@ -34,6 +35,9 @@ target_link_libraries(${PROJECT_NAME}
3435
${catkin_LIBRARIES}
3536
)
3637

38+
set(ROSLINT_CPP_OPTS "--filter=-build/c++14,-runtime/references")
39+
roslint_cpp()
40+
3741
## Install project namespaced headers
3842
install(DIRECTORY include/${PROJECT_NAME}/
3943
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
@@ -44,4 +48,8 @@ install(TARGETS ${PROJECT_NAME}
4448
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
4549
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
4650
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
47-
)
51+
)
52+
53+
if(CATKIN_ENABLE_TESTING)
54+
roslint_add_test()
55+
endif()

vector_map/include/vector_map/vector_map.h

+9-41
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717
#ifndef VECTOR_MAP_VECTOR_MAP_H
1818
#define VECTOR_MAP_VECTOR_MAP_H
1919

20-
#include <fstream>
2120
#include <ros/ros.h>
2221
#include <geometry_msgs/Point.h>
2322
#include <geometry_msgs/Quaternion.h>
@@ -56,6 +55,11 @@
5655
#include <vector_map_msgs/FenceArray.h>
5756
#include <vector_map_msgs/RailCrossingArray.h>
5857

58+
#include <fstream>
59+
#include <map>
60+
#include <string>
61+
#include <vector>
62+
5963
namespace vector_map
6064
{
6165
using vector_map_msgs::Point;
@@ -124,7 +128,7 @@ using vector_map_msgs::WallArray;
124128
using vector_map_msgs::FenceArray;
125129
using vector_map_msgs::RailCrossingArray;
126130

127-
using category_t = unsigned long long;
131+
using category_t = uint32_t;
128132

129133
enum Category : category_t
130134
{
@@ -297,7 +301,7 @@ std::vector<T> parse(const std::string& csv_file)
297301
{
298302
std::ifstream ifs(csv_file.c_str());
299303
std::string line;
300-
std::getline(ifs, line); // remove first line
304+
std::getline(ifs, line); // remove first line
301305
std::vector<T> objs;
302306
while (std::getline(ifs, line))
303307
{
@@ -309,42 +313,6 @@ std::vector<T> parse(const std::string& csv_file)
309313
return objs;
310314
}
311315

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-
348316
class VectorMap
349317
{
350318
private:
@@ -530,7 +498,7 @@ geometry_msgs::Point convertPointToGeomPoint(const Point& point);
530498
Point convertGeomPointToPoint(const geometry_msgs::Point& geom_point);
531499
geometry_msgs::Quaternion convertVectorToGeomQuaternion(const Vector& vector);
532500
Vector convertGeomQuaternionToVector(const geometry_msgs::Quaternion& geom_quaternion);
533-
} // namespace vector_map
501+
} // namespace vector_map
534502

535503
std::ostream& operator<<(std::ostream& os, const vector_map::Point& obj);
536504
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);
598566
std::istream& operator>>(std::istream& is, vector_map::Fence& obj);
599567
std::istream& operator>>(std::istream& is, vector_map::RailCrossing& obj);
600568

601-
#endif // VECTOR_MAP_VECTOR_MAP_H
569+
#endif // VECTOR_MAP_VECTOR_MAP_H

vector_map/lib/vector_map/vector_map.cpp

+10-6
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,10 @@
1717
#include <tf/transform_datatypes.h>
1818
#include <vector_map/vector_map.h>
1919

20+
#include <map>
21+
#include <string>
22+
#include <vector>
23+
2024
namespace vector_map
2125
{
2226
namespace
@@ -372,7 +376,7 @@ void updateRailCrossing(std::map<Key<RailCrossing>, RailCrossing>& map, const Ra
372376
map.insert(std::make_pair(Key<RailCrossing>(item.id), item));
373377
}
374378
}
375-
} // namespace
379+
} // namespace
376380

377381
bool VectorMap::hasSubscribed(category_t category) const
378382
{
@@ -1302,7 +1306,7 @@ std_msgs::ColorRGBA createColorRGBA(Color color)
13021306
color_rgba.b = COLOR_VALUE_MAX;
13031307
break;
13041308
default:
1305-
color_rgba.a = COLOR_VALUE_MIN; // hide color from view
1309+
color_rgba.a = COLOR_VALUE_MIN; // hide color from view
13061310
break;
13071311
}
13081312

@@ -1427,7 +1431,7 @@ visualization_msgs::Marker createAreaMarker(const std::string& ns, int id, Color
14271431
Line line = vmap.findByKey(Key<Line>(area.slid));
14281432
if (line.lid == 0)
14291433
return marker;
1430-
if (line.blid != 0) // must set beginning line
1434+
if (line.blid != 0) // must set beginning line
14311435
return marker;
14321436

14331437
while (line.flid != 0)
@@ -1611,8 +1615,8 @@ Point convertGeomPointToPoint(const geometry_msgs::Point& geom_point)
16111615

16121616
geometry_msgs::Quaternion convertVectorToGeomQuaternion(const Vector& vector)
16131617
{
1614-
double pitch = convertDegreeToRadian(vector.vang - 90); // convert vertical angle to pitch
1615-
double yaw = convertDegreeToRadian(-vector.hang + 90); // convert horizontal angle to yaw
1618+
double pitch = convertDegreeToRadian(vector.vang - 90); // convert vertical angle to pitch
1619+
double yaw = convertDegreeToRadian(-vector.hang + 90); // convert horizontal angle to yaw
16161620
return tf::createQuaternionMsgFromRollPitchYaw(0, pitch, yaw);
16171621
}
16181622

@@ -1626,7 +1630,7 @@ Vector convertGeomQuaternionToVector(const geometry_msgs::Quaternion& geom_quate
16261630
vector.hang = -convertRadianToDegree(yaw) + 90;
16271631
return vector;
16281632
}
1629-
} // namespace vector_map
1633+
} // namespace vector_map
16301634

16311635
std::ostream& operator<<(std::ostream& os, const vector_map::Point& obj)
16321636
{

vector_map/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@
1111

1212
<depend>geometry_msgs</depend>
1313
<depend>tf</depend>
14+
<depend>roslint</depend>
1415
<depend>vector_map_msgs</depend>
1516
<depend>visualization_msgs</depend>
1617
</package>

0 commit comments

Comments
 (0)