Skip to content

Commit 1d3e810

Browse files
committed
fix build werror
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 7205898 commit 1d3e810

File tree

3 files changed

+12
-15
lines changed

3 files changed

+12
-15
lines changed

evaluator/perception_evaluator/include/perception_evaluator/utils/marker_utils.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -63,8 +63,8 @@ MarkerArray createPoseMarkerArray(
6363
const float & b);
6464

6565
MarkerArray createPosesMarkerArray(
66-
const std::vector<Pose> poses, std::string && ns, const int32_t & id, const float & r,
67-
const float & g, const float & b, const float & x_scale = 0.5, const float & y_scale = 0.2,
66+
const std::vector<Pose> poses, std::string && ns, const float & r, const float & g,
67+
const float & b, const float & x_scale = 0.5, const float & y_scale = 0.2,
6868
const float & z_scale = 0.2);
6969

7070
std_msgs::msg::ColorRGBA createColorFromString(const std::string & str);
@@ -75,7 +75,7 @@ MarkerArray createObjectPolygonMarkerArray(
7575

7676
MarkerArray createDeviationLines(
7777
const std::vector<Pose> poses1, const std::vector<Pose> poses2, const std::string & ns,
78-
const int32_t id, const float r, const float g, const float b);
78+
const float r, const float g, const float b);
7979

8080
} // namespace marker_utils
8181

evaluator/perception_evaluator/src/perception_evaluator_node.cpp

+5-6
Original file line numberDiff line numberDiff line change
@@ -153,7 +153,7 @@ void PerceptionEvaluatorNode::publishDebugMarker()
153153
}
154154
if (p.show_history_path_arrows) {
155155
add(createPosesMarkerArray(
156-
history_path.first, "history_path_arrows_" + uuid, 0, c.r, c.g, c.b, 0.1, 0.05, 0.05));
156+
history_path.first, "history_path_arrows_" + uuid, c.r, c.g, c.b, 0.1, 0.05, 0.05));
157157
}
158158
}
159159
{
@@ -164,7 +164,7 @@ void PerceptionEvaluatorNode::publishDebugMarker()
164164
}
165165
if (p.show_smoothed_history_path_arrows) {
166166
add(createPosesMarkerArray(
167-
history_path.second, "smoothed_history_path_arrows_" + uuid, c.r, c.g, c.b, 0, 0.1, 0.05,
167+
history_path.second, "smoothed_history_path_arrows_" + uuid, c.r, c.g, c.b, 0.1, 0.05,
168168
0.05));
169169
}
170170
}
@@ -175,14 +175,13 @@ void PerceptionEvaluatorNode::publishDebugMarker()
175175
const auto predicted_path = object_data.getPredictedPath();
176176
const auto history_path = object_data.getHistoryPath();
177177
if (p.show_predicted_path) {
178-
add(createPosesMarkerArray(predicted_path, "predicted_path_" + uuid, 0, 0, 0, 1));
178+
add(createPosesMarkerArray(predicted_path, "predicted_path_" + uuid, 0, 0, 1));
179179
}
180180
if (p.show_predicted_path_gt) {
181-
add(createPosesMarkerArray(history_path, "predicted_path_gt_" + uuid, 0, 1, 0, 0));
181+
add(createPosesMarkerArray(history_path, "predicted_path_gt_" + uuid, 1, 0, 0));
182182
}
183183
if (p.show_deviation_lines) {
184-
add(
185-
createDeviationLines(predicted_path, history_path, "deviation_lines_" + uuid, 0, 1, 1, 1));
184+
add(createDeviationLines(predicted_path, history_path, "deviation_lines_" + uuid, 1, 1, 1));
186185
}
187186
if (p.show_object_polygon) {
188187
add(createObjectPolygonMarkerArray(

evaluator/perception_evaluator/src/utils/marker_utils.cpp

+4-6
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
1818
#include "tier4_autoware_utils/geometry/geometry.hpp"
1919

20-
#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp>
2120
#include <tier4_autoware_utils/ros/marker_helper.hpp>
2221
#include <tier4_autoware_utils/ros/uuid_helper.hpp>
2322

@@ -112,7 +111,7 @@ MarkerArray createPointsMarkerArray(
112111

113112
MarkerArray createDeviationLines(
114113
const std::vector<Pose> poses1, const std::vector<Pose> poses2, const std::string & ns,
115-
const int32_t id, const float r, const float g, const float b)
114+
const float r, const float g, const float b)
116115
{
117116
MarkerArray msg;
118117

@@ -145,15 +144,14 @@ MarkerArray createPoseMarkerArray(
145144
}
146145

147146
MarkerArray createPosesMarkerArray(
148-
const std::vector<Pose> poses, std::string && ns, const int32_t & id, const float & r,
149-
const float & g, const float & b, const float & x_scale, const float & y_scale,
150-
const float & z_scale)
147+
const std::vector<Pose> poses, std::string && ns, const float & r, const float & g,
148+
const float & b, const float & x_scale, const float & y_scale, const float & z_scale)
151149
{
152150
MarkerArray msg;
153151

154152
for (size_t i = 0; i < poses.size(); ++i) {
155153
Marker marker = createDefaultMarker(
156-
"map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, id + i, Marker::ARROW,
154+
"map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, i, Marker::ARROW,
157155
createMarkerScale(x_scale, y_scale, z_scale), createMarkerColor(r, g, b, 0.5));
158156
marker.pose = poses.at(i);
159157
msg.markers.push_back(marker);

0 commit comments

Comments
 (0)