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

fix(landmark_based_localizer): fix to for moving the definition code of landmarks #5803

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
63 changes: 1 addition & 62 deletions localization/landmark_based_localizer/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -43,68 +43,7 @@ So, if the 4 vertices are considered as forming a tetrahedron and its volume exc

## Map specifications

For this package to work correctly, the poses of the landmarks must be specified in the Lanelet2 map format that `map_loader` and `landmark_manager` can interpret.

The four vertices of a landmark are defined counterclockwise.

The order of the four vertices is defined as follows. In the coordinate system of a landmark,

- the x-axis is parallel to the vector from the first vertex to the second vertex
- the y-axis is parallel to the vector from the second vertex to the third vertex

![lanelet2 data structure](./doc_image/lanelet2_data_structure.drawio.svg)

### Example of `lanelet2_map.osm`

The values provided below are placeholders.
Ensure to input the correct coordinates corresponding to the actual location where the landmark is placed, such as `lat`, `lon`, `mgrs_code`, `local_x`, `local_y`.

For example, when using the AR tag, it would look like this.

```xml
...

<node id="1" lat="35.8xxxxx" lon="139.6xxxxx">
<tag k="mgrs_code" v="99XXX000000"/>
<tag k="local_x" v="22.2356"/>
<tag k="local_y" v="87.4506"/>
<tag k="ele" v="2.1725"/>
</node>
<node id="2" lat="35.8xxxxx" lon="139.6xxxxx">
<tag k="mgrs_code" v="99XXX000000"/>
<tag k="local_x" v="22.639"/>
<tag k="local_y" v="87.5886"/>
<tag k="ele" v="2.5947"/>
</node>
<node id="3" lat="35.8xxxxx" lon="139.6xxxxx">
<tag k="mgrs_code" v="99XXX000000"/>
<tag k="local_x" v="22.2331"/>
<tag k="local_y" v="87.4713"/>
<tag k="ele" v="3.0208"/>
</node>
<node id="4" lat="35.8xxxxx" lon="139.6xxxxx">
<tag k="mgrs_code" v="99XXX000000"/>
<tag k="local_x" v="21.8298"/>
<tag k="local_y" v="87.3332"/>
<tag k="ele" v="2.5985"/>
</node>

...

<way id="5">
<nd ref="1"/>
<nd ref="2"/>
<nd ref="3"/>
<nd ref="4"/>
<tag k="type" v="pose_marker"/>
<tag k="subtype" v="apriltag_16h5"/>
<tag k="area" v="yes"/>
<tag k="marker_id" v="0"/>
</way>

...

```
See <https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md#localization-landmarks>

## About `consider_orientation`

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@

void ArTagBasedLocalizer::map_bin_callback(const HADMapBin::ConstSharedPtr & msg)
{
landmark_manager_.parse_landmarks(msg, "apriltag_16h5", this->get_logger());
landmark_manager_.parse_landmarks(msg, "apriltag_16h5");
const MarkerArray marker_msg = landmark_manager_.get_landmarks_as_marker_array_msg();
mapped_tag_pose_pub_->publish(marker_msg);
}
Expand Down Expand Up @@ -173,7 +173,7 @@
const Pose self_pose = interpolate_result.value().interpolated_pose.pose.pose;

// detect
const std::vector<landmark_manager::Landmark> landmarks = detect_landmarks(msg);
const std::vector<Landmark> landmarks = detect_landmarks(msg);
if (landmarks.empty()) {
return;
}
Expand All @@ -183,7 +183,7 @@
PoseArray pose_array_msg;
pose_array_msg.header.stamp = sensor_stamp;
pose_array_msg.header.frame_id = "map";
for (const landmark_manager::Landmark & landmark : landmarks) {
for (const Landmark & landmark : landmarks) {
const Pose detected_marker_on_map =
tier4_autoware_utils::transformPose(landmark.pose, self_pose);
pose_array_msg.poses.push_back(detected_marker_on_map);
Expand Down Expand Up @@ -293,7 +293,7 @@
cv_ptr->image.copyTo(in_image);
} catch (cv_bridge::Exception & e) {
RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what());
return std::vector<landmark_manager::Landmark>{};
return std::vector<Landmark>{};

Check warning on line 296 in localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp

View check run for this annotation

Codecov / codecov/patch

localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp#L296

Added line #L296 was not covered by tests
}

// get transform from base_link to camera
Expand All @@ -303,15 +303,15 @@
tf_buffer_->lookupTransform("base_link", msg->header.frame_id, sensor_stamp);
} catch (tf2::TransformException & ex) {
RCLCPP_INFO(this->get_logger(), "Could not transform base_link to camera: %s", ex.what());
return std::vector<landmark_manager::Landmark>{};
return std::vector<Landmark>{};

Check warning on line 306 in localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp

View check run for this annotation

Codecov / codecov/patch

localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp#L306

Added line #L306 was not covered by tests
}

// detect
std::vector<aruco::Marker> markers;
detector_.detect(in_image, markers, cam_param_, marker_size_, false);

// parse
std::vector<landmark_manager::Landmark> landmarks;
std::vector<Landmark> landmarks;

for (aruco::Marker & marker : markers) {
// convert marker pose to tf
Expand All @@ -327,7 +327,7 @@
const double distance = std::hypot(pose.position.x, pose.position.y, pose.position.z);
if (distance <= distance_threshold_) {
tf2::doTransform(pose, pose, transform_sensor_to_base_link);
landmarks.push_back(landmark_manager::Landmark{std::to_string(marker.id), pose});
landmarks.push_back(Landmark{std::to_string(marker.id), pose});
}

// for debug, drawing the detected markers
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,7 @@ class ArTagBasedLocalizer : public rclcpp::Node
using TransformStamped = geometry_msgs::msg::TransformStamped;
using MarkerArray = visualization_msgs::msg::MarkerArray;
using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray;
using Landmark = landmark_manager::Landmark;

public:
explicit ArTagBasedLocalizer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
Expand All @@ -89,7 +90,7 @@ class ArTagBasedLocalizer : public rclcpp::Node
void image_callback(const Image::ConstSharedPtr & msg);
void cam_info_callback(const CameraInfo::ConstSharedPtr & msg);
void ekf_pose_callback(const PoseWithCovarianceStamped::ConstSharedPtr & msg);
std::vector<landmark_manager::Landmark> detect_landmarks(const Image::ConstSharedPtr & msg);
std::vector<Landmark> detect_landmarks(const Image::ConstSharedPtr & msg);

// Parameters
float marker_size_{};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#ifndef LANDMARK_MANAGER__LANDMARK_MANAGER_HPP_
#define LANDMARK_MANAGER__LANDMARK_MANAGER_HPP_

#include "lanelet2_extension/localization/landmark.hpp"

#include <rclcpp/rclcpp.hpp>

#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp"
Expand All @@ -40,13 +42,13 @@ class LandmarkManager
public:
void parse_landmarks(
const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg,
const std::string & target_subtype, const rclcpp::Logger & logger);
const std::string & target_subtype);

[[nodiscard]] visualization_msgs::msg::MarkerArray get_landmarks_as_marker_array_msg() const;

[[nodiscard]] geometry_msgs::msg::Pose calculate_new_self_pose(
const std::vector<landmark_manager::Landmark> & detected_landmarks,
const geometry_msgs::msg::Pose & self_pose, const bool consider_orientation) const;
const std::vector<Landmark> & detected_landmarks, const geometry_msgs::msg::Pose & self_pose,
const bool consider_orientation) const;

private:
// To allow multiple landmarks with the same id to be registered on a vector_map,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,32 +29,17 @@

void LandmarkManager::parse_landmarks(
const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg,
const std::string & target_subtype, const rclcpp::Logger & logger)
const std::string & target_subtype)
{
RCLCPP_INFO_STREAM(logger, "msg->format_version: " << msg->format_version);
RCLCPP_INFO_STREAM(logger, "msg->map_format: " << msg->map_format);
RCLCPP_INFO_STREAM(logger, "msg->map_version: " << msg->map_version);
RCLCPP_INFO_STREAM(logger, "msg->data.size(): " << msg->data.size());
lanelet::LaneletMapPtr lanelet_map_ptr{std::make_shared<lanelet::LaneletMap>()};
lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr);

for (const auto & poly : lanelet_map_ptr->polygonLayer) {
const std::string type{poly.attributeOr(lanelet::AttributeName::Type, "none")};
if (type != "pose_marker") {
continue;
}
const std::string subtype{poly.attributeOr(lanelet::AttributeName::Subtype, "none")};
if (subtype != target_subtype) {
continue;
}

std::vector<lanelet::Polygon3d> landmarks =
lanelet::localization::parseLandmarkPolygons(msg, target_subtype);

Check warning on line 35 in localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp

View check run for this annotation

Codecov / codecov/patch

localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp#L35

Added line #L35 was not covered by tests
for (const lanelet::Polygon3d & poly : landmarks) {
// Get landmark_id
const std::string landmark_id = poly.attributeOr("marker_id", "none");

// Get 4 vertices
const auto & vertices = poly.basicPolygon();
if (vertices.size() != 4) {
RCLCPP_WARN_STREAM(logger, "vertices.size() (" << vertices.size() << ") != 4");
continue;
}

Expand All @@ -65,12 +50,8 @@
const auto & v2 = vertices[2];
const auto & v3 = vertices[3];
const double volume = (v1 - v0).cross(v2 - v0).dot(v3 - v0) / 6.0;
RCLCPP_INFO_STREAM(logger, "volume = " << volume);
const double volume_threshold = 1e-5;
if (volume > volume_threshold) {
RCLCPP_WARN_STREAM(
logger,
"volume (" << volume << ") > threshold (" << volume_threshold << "), This is not plane.");
continue;
}

Expand Down Expand Up @@ -99,13 +80,6 @@

// Add
landmarks_map_[landmark_id].push_back(pose);

Check notice on line 82 in localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Complex Method

LandmarkManager::parse_landmarks is no longer above the threshold for cyclomatic complexity
RCLCPP_INFO_STREAM(logger, "id: " << landmark_id);
RCLCPP_INFO_STREAM(
logger,
"(x, y, z) = " << pose.position.x << ", " << pose.position.y << ", " << pose.position.z);
RCLCPP_INFO_STREAM(
logger, "q = " << pose.orientation.x << ", " << pose.orientation.y << ", "
<< pose.orientation.z << ", " << pose.orientation.w);
}
}

Expand Down
Loading