Skip to content

fix(autoware_landmark_manager): fix deprecated autoware_utils header #10515

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

Open
wants to merge 10 commits into
base: main
Choose a base branch
from
Open
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<depend>aruco</depend>
<depend>autoware_landmark_manager</depend>
<depend>autoware_localization_util</depend>
<depend>autoware_utils_geometry</depend>
<depend>cv_bridge</depend>
<depend>diagnostic_msgs</depend>
<depend>rclcpp</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@
#include <tf2_eigen/tf2_eigen.hpp>
#endif

#include <autoware_utils/geometry/geometry.hpp>
#include <autoware_utils_geometry/geometry.hpp>

ArTagBasedLocalizer::ArTagBasedLocalizer(const rclcpp::NodeOptions & options)
: rclcpp::Node("ar_tag_based_localizer", options), cam_info_received_(false)
Expand Down Expand Up @@ -192,16 +192,17 @@
pose_array_msg.header.stamp = sensor_stamp;
pose_array_msg.header.frame_id = "map";
for (const Landmark & landmark : landmarks) {
const Pose detected_marker_on_map = autoware_utils::transform_pose(landmark.pose, self_pose);
const Pose detected_marker_on_map =
autoware_utils_geometry::transform_pose(landmark.pose, self_pose);
pose_array_msg.poses.push_back(detected_marker_on_map);
}
detected_tag_pose_pub_->publish(pose_array_msg);
}

// calc new_self_pose
const Pose new_self_pose =
landmark_manager_.calculate_new_self_pose(landmarks, self_pose, consider_orientation_);
const Pose diff_pose = autoware_utils::inverse_transform_pose(new_self_pose, self_pose);
const Pose diff_pose = autoware_utils_geometry::inverse_transform_pose(new_self_pose, self_pose);

Check warning on line 205 in localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/src/ar_tag_based_localizer.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

ArTagBasedLocalizer::image_callback already has high cyclomatic complexity, and now it increases in Lines of Code from 70 to 71. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
const double distance =
std::hypot(diff_pose.position.x, diff_pose.position.y, diff_pose.position.z);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_localization_util</depend>
<depend>autoware_map_msgs</depend>
<depend>autoware_utils</depend>
<depend>autoware_utils_geometry</depend>
<depend>geometry_msgs</depend>
<depend>rclcpp</depend>
<depend>tf2_eigen</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include "autoware/localization_util/util_func.hpp"
#include "autoware_lanelet2_extension/utility/message_conversion.hpp"
#include "autoware_utils/geometry/geometry.hpp"
#include "autoware_utils_geometry/geometry.hpp"

#include <Eigen/Core>
#include <tf2_eigen/tf2_eigen.hpp>
Expand Down Expand Up @@ -165,7 +165,7 @@

// convert base_link to map
const Pose detected_landmark_on_map =
autoware_utils::transform_pose(detected_landmark_on_base_link, self_pose);
autoware_utils_geometry::transform_pose(detected_landmark_on_base_link, self_pose);

Check warning on line 168 in localization/autoware_landmark_based_localizer/autoware_landmark_manager/src/landmark_manager.cpp

View check run for this annotation

Codecov / codecov/patch

localization/autoware_landmark_based_localizer/autoware_landmark_manager/src/landmark_manager.cpp#L168

Added line #L168 was not covered by tests

// match to map
if (landmarks_map_.count(landmark.id) == 0) {
Expand All @@ -175,7 +175,7 @@
// check all poses
for (const Pose mapped_landmark_on_map : landmarks_map_.at(landmark.id)) {
// check distance
const double curr_distance = autoware_utils::calc_distance3d(
const double curr_distance = autoware_utils_geometry::calc_distance3d(

Check warning on line 178 in localization/autoware_landmark_based_localizer/autoware_landmark_manager/src/landmark_manager.cpp

View check run for this annotation

Codecov / codecov/patch

localization/autoware_landmark_based_localizer/autoware_landmark_manager/src/landmark_manager.cpp#L178

Added line #L178 was not covered by tests
mapped_landmark_on_map.position, detected_landmark_on_map.position);
if (curr_distance > min_distance) {
continue;
Expand Down
Loading