Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_auto_perception_rviz_plugin): indicate object orientation, parameter adjustments, bugfix #6469

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -186,6 +186,10 @@ AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_bounding_box_direction_lin
const autoware_auto_perception_msgs::msg::Shape & shape,
std::vector<geometry_msgs::msg::Point> & points);

AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_bounding_box_orientation_line_list(
const autoware_auto_perception_msgs::msg::Shape & shape,
std::vector<geometry_msgs::msg::Point> & points);

AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_2d_bounding_box_bottom_line_list(
const autoware_auto_perception_msgs::msg::Shape & shape,
std::vector<geometry_msgs::msg::Point> & points);
Expand All @@ -194,6 +198,10 @@ AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_2d_bounding_box_bottom_dir
const autoware_auto_perception_msgs::msg::Shape & shape,
std::vector<geometry_msgs::msg::Point> & points);

AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_2d_bounding_box_bottom_orientation_line_list(
const autoware_auto_perception_msgs::msg::Shape & shape,
std::vector<geometry_msgs::msg::Point> & points);

AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_cylinder_line_list(
const autoware_auto_perception_msgs::msg::Shape & shape,
std::vector<geometry_msgs::msg::Point> & points);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Apex.AI, Inc.

Check notice on line 1 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Primitive Obsession

The ratio of primitive types in function arguments decreases from 33.33% to 31.91%, threshold = 30.0%. The functions in this file have too many primitive types (e.g. int, double, float) in their function argument lists. Using many primitive types lead to the code smell Primitive Obsession. Avoid adding more primitive arguments.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -57,7 +57,7 @@
marker_ptr->type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING;
marker_ptr->ns = std::string("path confidence");
marker_ptr->action = visualization_msgs::msg::Marker::MODIFY;
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 60 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L60

Added line #L60 was not covered by tests
marker_ptr->scale.x = 0.5;
marker_ptr->scale.y = 0.5;
marker_ptr->scale.z = 0.5;
Expand All @@ -78,14 +78,14 @@
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
marker_ptr->ns = std::string("path");
marker_ptr->action = visualization_msgs::msg::Marker::MODIFY;
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 81 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L81

Added line #L81 was not covered by tests
marker_ptr->pose = initPose();
marker_ptr->color = predicted_path_color;
marker_ptr->color.a = 0.6;
marker_ptr->scale.x = 0.015;
calc_path_line_list(predicted_path, marker_ptr->points, is_simple);
for (size_t k = 0; k < marker_ptr->points.size(); ++k) {
marker_ptr->points.at(k).z -= shape.dimensions.z / 2.0;
marker_ptr->points.at(k).z -= shape.dimensions.z * 0.5;

Check warning on line 88 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L88

Added line #L88 was not covered by tests
}
return marker_ptr;
}
Expand All @@ -112,7 +112,7 @@
point.z = twist_with_covariance.twist.linear.z;
marker_ptr->points.push_back(point);

marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 115 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L115

Added line #L115 was not covered by tests
marker_ptr->color.a = 0.999;
marker_ptr->color.r = 1.0;
marker_ptr->color.g = 0.0;
Expand Down Expand Up @@ -160,19 +160,19 @@
// ellipse orientation
marker_ptr->pose.orientation.x = 0.0;
marker_ptr->pose.orientation.y = 0.0;
marker_ptr->pose.orientation.z = std::sin(phi / 2.0);
marker_ptr->pose.orientation.w = std::cos(phi / 2.0);
marker_ptr->pose.orientation.z = std::sin(phi * 0.5);
marker_ptr->pose.orientation.w = std::cos(phi * 0.5);

Check warning on line 164 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L163-L164

Added lines #L163 - L164 were not covered by tests

// ellipse size
marker_ptr->scale.x = sigma1 * confidence_interval_coefficient;
marker_ptr->scale.y = sigma2 * confidence_interval_coefficient;
marker_ptr->scale.z = 0.05;

marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 171 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L171

Added line #L171 was not covered by tests
marker_ptr->color.a = alpha;
marker_ptr->color.r = 1.0;
marker_ptr->color.g = 0.2;
marker_ptr->color.b = 0.4;
marker_ptr->color.r = 0.2;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

[imo, you can ignore this] If possible, I prefer there are some comments about color description because we can't image color from rgb values :)

marker_ptr->color.g = 0.4;
marker_ptr->color.b = 0.9;

Check warning on line 175 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L173-L175

Added lines #L173 - L175 were not covered by tests

return marker_ptr;
}
Expand Down Expand Up @@ -213,7 +213,7 @@
point.z = 0;
marker_ptr->points.push_back(point);

marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 216 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L216

Added line #L216 was not covered by tests
marker_ptr->color.a = 0.9;
marker_ptr->color.r = 1.0;
marker_ptr->color.g = 0.0;
Expand Down Expand Up @@ -274,7 +274,7 @@
};
calc_line_list_from_points(point_list, point_pairs, 4, marker_ptr->points);

marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 277 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L277

Added line #L277 was not covered by tests
marker_ptr->color.a = 0.9;
marker_ptr->color.r = 1.0;
marker_ptr->color.g = 0.2;
Expand All @@ -299,7 +299,7 @@
marker_ptr->text = std::to_string(static_cast<int>(vel * 3.6)) + std::string("[km/h]");
marker_ptr->action = visualization_msgs::msg::Marker::MODIFY;
marker_ptr->pose.position = vis_pos;
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 302 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L302

Added line #L302 was not covered by tests
marker_ptr->color = color_rgba;
return marker_ptr;
}
Expand All @@ -320,7 +320,7 @@
marker_ptr->text = getRoundedDoubleString(acc) + std::string("[m/s^2]");
marker_ptr->action = visualization_msgs::msg::Marker::MODIFY;
marker_ptr->pose.position = vis_pos;
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 323 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L323

Added line #L323 was not covered by tests
marker_ptr->color = color_rgba;
return marker_ptr;
}
Expand Down Expand Up @@ -378,8 +378,8 @@
// ellipse orientation
marker_ptr->pose.orientation.x = 0.0;
marker_ptr->pose.orientation.y = 0.0;
marker_ptr->pose.orientation.z = std::sin(yaw / 2.0);
marker_ptr->pose.orientation.w = std::cos(yaw / 2.0);
marker_ptr->pose.orientation.z = std::sin(yaw * 0.5);
marker_ptr->pose.orientation.w = std::cos(yaw * 0.5);

Check warning on line 382 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L381-L382

Added lines #L381 - L382 were not covered by tests

// ellipse size
marker_ptr->scale.x = sigma1 * confidence_interval_coefficient;
Expand All @@ -392,11 +392,11 @@
alpha = std::max(0.1, alpha);

// marker configuration
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 395 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L395

Added line #L395 was not covered by tests
marker_ptr->color.a = alpha;
marker_ptr->color.r = 1.0;
marker_ptr->color.g = 1.0;
marker_ptr->color.b = 1.0;
marker_ptr->color.r = 0.8;
marker_ptr->color.g = 0.8;
marker_ptr->color.b = 0.8;

Check warning on line 399 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L397-L399

Added lines #L397 - L399 were not covered by tests
return marker_ptr;
}

Expand Down Expand Up @@ -434,7 +434,7 @@
marker_ptr->points.push_back(point);

// marker configuration
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 437 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L437

Added line #L437 was not covered by tests
marker_ptr->color.a = 0.9;
marker_ptr->color.r = 1.0;
marker_ptr->color.g = 1.0;
Expand Down Expand Up @@ -469,7 +469,7 @@
marker_ptr->text = label;
marker_ptr->action = visualization_msgs::msg::Marker::MODIFY;
marker_ptr->pose = marker_ptr->pose = to_pose(centroid, orientation);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 472 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L472

Added line #L472 was not covered by tests
marker_ptr->color = color_rgba;
return marker_ptr;
}
Expand All @@ -486,7 +486,7 @@
marker_ptr->text = std::to_string(existence_probability);
marker_ptr->action = visualization_msgs::msg::Marker::MODIFY;
marker_ptr->pose = marker_ptr->pose = to_pose(centroid, orientation);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.2);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 489 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L489

Added line #L489 was not covered by tests
marker_ptr->color = color_rgba;
return marker_ptr;
}
Expand All @@ -506,6 +506,8 @@
calc_bounding_box_line_list(shape_msg, marker_ptr->points);
if (is_orientation_available) {
calc_bounding_box_direction_line_list(shape_msg, marker_ptr->points);
} else {
calc_bounding_box_orientation_line_list(shape_msg, marker_ptr->points);

Check warning on line 510 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L510

Added line #L510 was not covered by tests
}
} else if (shape_msg.type == Shape::CYLINDER) {
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
Expand All @@ -520,7 +522,7 @@

marker_ptr->action = visualization_msgs::msg::Marker::MODIFY;
marker_ptr->pose = to_pose(centroid, orientation);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 525 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L525

Added line #L525 was not covered by tests
marker_ptr->scale.x = line_width;
marker_ptr->color = color_rgba;

Expand All @@ -542,6 +544,8 @@
calc_2d_bounding_box_bottom_line_list(shape_msg, marker_ptr->points);
if (is_orientation_available) {
calc_2d_bounding_box_bottom_direction_line_list(shape_msg, marker_ptr->points);
} else {
calc_2d_bounding_box_bottom_orientation_line_list(shape_msg, marker_ptr->points);

Check warning on line 548 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L548

Added line #L548 was not covered by tests
}
} else if (shape_msg.type == Shape::CYLINDER) {
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
Expand All @@ -556,7 +560,7 @@

marker_ptr->action = visualization_msgs::msg::Marker::MODIFY;
marker_ptr->pose = to_pose(centroid, orientation);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);

Check warning on line 563 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L563

Added line #L563 was not covered by tests
marker_ptr->scale.x = line_width;
marker_ptr->color = color_rgba;

Expand Down Expand Up @@ -584,9 +588,9 @@
const autoware_auto_perception_msgs::msg::Shape & shape,
std::vector<geometry_msgs::msg::Point> & points)
{
const double length_half = shape.dimensions.x / 2.0;
const double width_half = shape.dimensions.y / 2.0;
const double height_half = shape.dimensions.z / 2.0;
const double length_half = shape.dimensions.x * 0.5;
const double width_half = shape.dimensions.y * 0.5;
const double height_half = shape.dimensions.z * 0.5;

Check warning on line 593 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L591-L593

Added lines #L591 - L593 were not covered by tests
geometry_msgs::msg::Point point;

// bounding box corner points
Expand All @@ -608,10 +612,10 @@
std::vector<geometry_msgs::msg::Point> & points)
{
// direction triangle
const double length_half = shape.dimensions.x / 2.0;
const double width_half = shape.dimensions.y / 2.0;
const double height_half = shape.dimensions.z / 2.0;
const double triangle_size_half = shape.dimensions.y / 1.4;
const double length_half = shape.dimensions.x * 0.5;
const double width_half = shape.dimensions.y * 0.5;
const double height_half = shape.dimensions.z * 0.5;
const double triangle_size_half = std::min(width_half * 1.4, shape.dimensions.x);

Check warning on line 618 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L615-L618

Added lines #L615 - L618 were not covered by tests
geometry_msgs::msg::Point point;

// triangle-shaped direction indicator
Expand All @@ -629,13 +633,38 @@
calc_line_list_from_points(point_list, point_pairs, 5, points);
}

void calc_bounding_box_orientation_line_list(

Check warning on line 636 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L636

Added line #L636 was not covered by tests
const autoware_auto_perception_msgs::msg::Shape & shape,
std::vector<geometry_msgs::msg::Point> & points)
{
const double length_half = shape.dimensions.x * 0.5;
const double width_half = shape.dimensions.y * 0.5;
const double height_half = shape.dimensions.z * 0.5;
const double tick_width = width_half * 0.5;
const double tick_length = std::min(tick_width, length_half);

Check warning on line 644 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L640-L644

Added lines #L640 - L644 were not covered by tests
geometry_msgs::msg::Point point;

// front corner cuts for orientation
const double point_list[4][3] = {
{length_half, width_half - tick_width, height_half},
{length_half - tick_length, width_half, height_half},
{length_half, -width_half + tick_width, height_half},
{length_half - tick_length, -width_half, height_half},
};
const int point_pairs[2][2] = {

Check warning on line 654 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L649-L654

Added lines #L649 - L654 were not covered by tests
{0, 1},
{2, 3},
};
calc_line_list_from_points(point_list, point_pairs, 2, points);
}

Check warning on line 659 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L658-L659

Added lines #L658 - L659 were not covered by tests

void calc_2d_bounding_box_bottom_line_list(
const autoware_auto_perception_msgs::msg::Shape & shape,
std::vector<geometry_msgs::msg::Point> & points)
{
const double length_half = shape.dimensions.x / 2.0;
const double width_half = shape.dimensions.y / 2.0;
const double height_half = shape.dimensions.z / 2.0;
const double length_half = shape.dimensions.x * 0.5;
const double width_half = shape.dimensions.y * 0.5;
const double height_half = shape.dimensions.z * 0.5;

Check warning on line 667 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Code Duplication

introduced similar code in: calc_2d_bounding_box_bottom_orientation_line_list,calc_bounding_box_orientation_line_list. Avoid duplicated, aka copy-pasted, code inside the module. More duplication lowers the code health.

Check warning on line 667 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L665-L667

Added lines #L665 - L667 were not covered by tests
geometry_msgs::msg::Point point;

// bounding box corner points
Expand All @@ -659,10 +688,10 @@
const autoware_auto_perception_msgs::msg::Shape & shape,
std::vector<geometry_msgs::msg::Point> & points)
{
const double length_half = shape.dimensions.x / 2.0;
const double width_half = shape.dimensions.y / 2.0;
const double height_half = shape.dimensions.z / 2.0;
const double triangle_size_half = shape.dimensions.y / 1.4;
const double length_half = shape.dimensions.x * 0.5;
const double width_half = shape.dimensions.y * 0.5;
const double height_half = shape.dimensions.z * 0.5;
const double triangle_size_half = std::min(width_half * 1.4, shape.dimensions.x);

Check warning on line 694 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L691-L694

Added lines #L691 - L694 were not covered by tests
geometry_msgs::msg::Point point;

// triangle-shaped direction indicator
Expand All @@ -679,6 +708,31 @@
calc_line_list_from_points(point_list, point_pairs, 3, points);
}

void calc_2d_bounding_box_bottom_orientation_line_list(

Check warning on line 711 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L711

Added line #L711 was not covered by tests
const autoware_auto_perception_msgs::msg::Shape & shape,
std::vector<geometry_msgs::msg::Point> & points)
{
const double length_half = shape.dimensions.x * 0.5;
const double width_half = shape.dimensions.y * 0.5;
const double height_half = shape.dimensions.z * 0.5;
const double tick_width = width_half * 0.5;
const double tick_length = std::min(tick_width, length_half);

Check warning on line 719 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L715-L719

Added lines #L715 - L719 were not covered by tests
geometry_msgs::msg::Point point;

// front corner cuts for orientation
const double point_list[4][3] = {
{length_half, width_half - tick_width, height_half},
{length_half - tick_length, width_half, height_half},
{length_half, -width_half + tick_width, height_half},
{length_half - tick_length, -width_half, height_half},
};
const int point_pairs[2][2] = {

Check warning on line 729 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L724-L729

Added lines #L724 - L729 were not covered by tests
{0, 1},
{2, 3},
};
calc_line_list_from_points(point_list, point_pairs, 2, points);
}

Check warning on line 734 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L733-L734

Added lines #L733 - L734 were not covered by tests

void calc_cylinder_line_list(
const autoware_auto_perception_msgs::msg::Shape & shape,
std::vector<geometry_msgs::msg::Point> & points)
Expand Down Expand Up @@ -784,41 +838,41 @@
geometry_msgs::msg::Point point;
point.x = shape.footprint.points.at(i).x;
point.y = shape.footprint.points.at(i).y;
point.z = shape.dimensions.z / 2.0;
point.z = shape.dimensions.z * 0.5;

Check warning on line 841 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L841

Added line #L841 was not covered by tests
points.push_back(point);
point.x = shape.footprint.points
.at(static_cast<int>(i + 1) % static_cast<int>(shape.footprint.points.size()))
.x;
point.y = shape.footprint.points
.at(static_cast<int>(i + 1) % static_cast<int>(shape.footprint.points.size()))
.y;
point.z = shape.dimensions.z / 2.0;
point.z = shape.dimensions.z * 0.5;

Check warning on line 849 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L849

Added line #L849 was not covered by tests
points.push_back(point);
}
for (size_t i = 0; i < shape.footprint.points.size(); ++i) {
geometry_msgs::msg::Point point;
point.x = shape.footprint.points.at(i).x;
point.y = shape.footprint.points.at(i).y;
point.z = -shape.dimensions.z / 2.0;
point.z = -shape.dimensions.z * 0.5;

Check warning on line 856 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L856

Added line #L856 was not covered by tests
points.push_back(point);
point.x = shape.footprint.points
.at(static_cast<int>(i + 1) % static_cast<int>(shape.footprint.points.size()))
.x;
point.y = shape.footprint.points
.at(static_cast<int>(i + 1) % static_cast<int>(shape.footprint.points.size()))
.y;
point.z = -shape.dimensions.z / 2.0;
point.z = -shape.dimensions.z * 0.5;

Check warning on line 864 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L864

Added line #L864 was not covered by tests
points.push_back(point);
}
for (size_t i = 0; i < shape.footprint.points.size(); ++i) {
geometry_msgs::msg::Point point;
point.x = shape.footprint.points.at(i).x;
point.y = shape.footprint.points.at(i).y;
point.z = shape.dimensions.z / 2.0;
point.z = shape.dimensions.z * 0.5;

Check warning on line 871 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L871

Added line #L871 was not covered by tests
points.push_back(point);
point.x = shape.footprint.points.at(i).x;
point.y = shape.footprint.points.at(i).y;
point.z = -shape.dimensions.z / 2.0;
point.z = -shape.dimensions.z * 0.5;

Check warning on line 875 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L875

Added line #L875 was not covered by tests
points.push_back(point);
}
}
Expand All @@ -837,15 +891,15 @@
geometry_msgs::msg::Point point;
point.x = shape.footprint.points.at(i).x;
point.y = shape.footprint.points.at(i).y;
point.z = -shape.dimensions.z / 2.0;
point.z = -shape.dimensions.z * 0.5;

Check warning on line 894 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L894

Added line #L894 was not covered by tests
points.push_back(point);
point.x = shape.footprint.points
.at(static_cast<int>(i + 1) % static_cast<int>(shape.footprint.points.size()))
.x;
point.y = shape.footprint.points
.at(static_cast<int>(i + 1) % static_cast<int>(shape.footprint.points.size()))
.y;
point.z = -shape.dimensions.z / 2.0;
point.z = -shape.dimensions.z * 0.5;

Check warning on line 902 in common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp#L902

Added line #L902 was not covered by tests
points.push_back(point);
}
}
Expand Down
Loading
Loading