Skip to content

Commit f9d7838

Browse files
Joshua WhitleyGeoffrey Biggs
Joshua Whitley
authored and
Geoffrey Biggs
committed
Adding roslint to vector_map_server and applying (most) suggestions.
1 parent 35ba382 commit f9d7838

File tree

4 files changed

+27
-16
lines changed

4 files changed

+27
-16
lines changed

vector_map_server/CMakeLists.txt

+11-3
Original file line numberDiff line numberDiff line change
@@ -4,13 +4,14 @@ project(vector_map_server)
44
find_package(autoware_build_flags REQUIRED)
55

66
find_package(catkin REQUIRED COMPONENTS
7-
roscpp
7+
autoware_msgs
88
geometry_msgs
9-
visualization_msgs
109
message_generation
10+
roscpp
11+
roslint
1112
vector_map
12-
autoware_msgs
1313
vector_map_msgs
14+
visualization_msgs
1415
)
1516

1617
set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}")
@@ -93,8 +94,15 @@ add_dependencies(vector_map_client
9394
${catkin_EXPORTED_TARGETS}
9495
)
9596

97+
set(ROSLINT_CPP_OPTS "--filter=-build/c++14,-runtime/references,-whitespace/braces")
98+
roslint_cpp()
99+
96100
install(TARGETS ${PROJECT_NAME} vector_map_client
97101
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
98102
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
99103
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
100104
)
105+
106+
if(CATKIN_ENABLE_TESTING)
107+
roslint_add_test()
108+
endif()

vector_map_server/nodes/vector_map_client/vector_map_client.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,9 @@
1515
*/
1616

1717
#include <geometry_msgs/PoseStamped.h>
18-
#include "autoware_msgs/Lane.h"
18+
#include <autoware_msgs/Lane.h>
1919
#include <visualization_msgs/MarkerArray.h>
20-
#include "vector_map/vector_map.h"
20+
#include <vector_map/vector_map.h>
2121

2222
#include "vector_map_server/GetWhiteLine.h"
2323
#include "vector_map_server/GetStopLine.h"
@@ -74,7 +74,7 @@ class VectorMapClient
7474
waypoints_ = waypoints;
7575
}
7676
};
77-
} // namespace
77+
} // namespace
7878

7979
int main(int argc, char **argv)
8080
{
@@ -89,7 +89,7 @@ int main(int argc, char **argv)
8989
vmap.subscribe(nh,
9090
Category::POINT | Category::VECTOR | Category::LINE | Category::AREA | Category::POLE |
9191
Category::WHITE_LINE | Category::STOP_LINE | Category::CROSS_WALK | Category::SIGNAL,
92-
ros::Duration(0)); // non-blocking
92+
ros::Duration(0)); // non-blocking
9393

9494
ros::Subscriber pose_sub = nh.subscribe("current_pose", 1, &VectorMapClient::setPose, &vmc);
9595
ros::Subscriber waypoints_sub = nh.subscribe("final_waypoints", 1, &VectorMapClient::setWaypoints, &vmc);
@@ -264,7 +264,7 @@ int main(int argc, char **argv)
264264
{
265265
for (auto& marker : marker_array.markers)
266266
marker.action = visualization_msgs::Marker::DELETE;
267-
marker_array_pub.publish(marker_array); // clear previous marker
267+
marker_array_pub.publish(marker_array); // clear previous marker
268268
}
269269
marker_array = marker_array_buffer;
270270
marker_array_pub.publish(marker_array);

vector_map_server/nodes/vector_map_server/vector_map_server.cpp

+10-8
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,9 @@
1515
*/
1616

1717
#include <geometry_msgs/PoseStamped.h>
18-
#include "autoware_msgs/Lane.h"
18+
#include <autoware_msgs/Lane.h>
1919
#include <visualization_msgs/MarkerArray.h>
20-
#include "vector_map/vector_map.h"
20+
#include <vector_map/vector_map.h>
2121

2222
#include "vector_map_server/GetDTLane.h"
2323
#include "vector_map_server/GetNode.h"
@@ -47,6 +47,8 @@
4747
#include "vector_map_server/GetRailCrossing.h"
4848
#include "vector_map_server/PositionState.h"
4949

50+
#include <vector>
51+
5052
using vector_map::VectorMap;
5153
using vector_map::Category;
5254
using vector_map::Color;
@@ -106,12 +108,12 @@ bool isMergingLane(const Lane& lane)
106108

107109
double computeDistance(const Point& p1, const Point& p2)
108110
{
109-
return std::hypot(p2.bx - p1.bx, p2.ly - p1.ly); // XXX: don't consider z axis
111+
return std::hypot(p2.bx - p1.bx, p2.ly - p1.ly); // XXX: don't consider z axis
110112
}
111113

112114
double computeAngle(const Point& p1, const Point& p2)
113115
{
114-
return std::atan2(p2.ly - p1.ly, p2.bx - p1.bx); // XXX: don't consider z axis
116+
return std::atan2(p2.ly - p1.ly, p2.bx - p1.bx); // XXX: don't consider z axis
115117
}
116118

117119
double computeScore(const Point& bp1, const Point& bp2, const Point& p1, const Point& p2, double radius)
@@ -362,7 +364,7 @@ std::vector<Lane> createFineLanes(const VectorMap& vmap, const autoware_msgs::La
362364
if (fine_p1.pid == 0)
363365
return null_lanes;
364366

365-
Point coarse_p1 = findNearestPoint(coarse_points, fine_p1); // certainly succeed
367+
Point coarse_p1 = findNearestPoint(coarse_points, fine_p1); // certainly succeed
366368

367369
if (computeDistance(fine_p1, coarse_p1) > radius)
368370
return null_lanes;
@@ -373,7 +375,7 @@ std::vector<Lane> createFineLanes(const VectorMap& vmap, const autoware_msgs::La
373375
{
374376
if (distance == -DBL_MAX)
375377
{
376-
if (coarse_point.bx == coarse_p1.bx && coarse_point.ly == coarse_p1.ly) // XXX: don't consider z axis
378+
if (coarse_point.bx == coarse_p1.bx && coarse_point.ly == coarse_p1.ly) // XXX: don't consider z axis
377379
distance = 0;
378380
continue;
379381
}
@@ -574,7 +576,7 @@ class VectorMapServer
574576
{
575577
for (auto& marker : marker_array_.markers)
576578
marker.action = visualization_msgs::Marker::DELETE;
577-
marker_array_pub_.publish(marker_array_); // clear previous marker
579+
marker_array_pub_.publish(marker_array_); // clear previous marker
578580
}
579581
marker_array_ = marker_array_buffer;
580582
marker_array_pub_.publish(marker_array_);
@@ -1033,7 +1035,7 @@ class VectorMapServer
10331035
return true;
10341036
}
10351037
};
1036-
} // namespace
1038+
} // namespace
10371039

10381040
int main(int argc, char **argv)
10391041
{

vector_map_server/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212

1313
<depend>autoware_msgs</depend>
1414
<depend>geometry_msgs</depend>
15+
<depend>roslint</depend>
1516
<depend>vector_map</depend>
1617
<depend>vector_map_msgs</depend>
1718
<depend>visualization_msgs</depend>

0 commit comments

Comments
 (0)