Skip to content

Commit

Permalink
feat(map_loader): visualize center line by points (tier4#931)
Browse files Browse the repository at this point in the history
* feat: visualize center line points

* fix: delete space

* feat: visualize center line by arrow

* revert insertMarkerArray

* fix: delete space
  • Loading branch information
h-ohta authored and boyali committed Oct 19, 2022
1 parent c989b1c commit e81d4e3
Show file tree
Hide file tree
Showing 2 changed files with 66 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,16 @@ void pushLineStringMarker(
visualization_msgs::msg::Marker * marker, const lanelet::ConstLineString3d & ls,
const std_msgs::msg::ColorRGBA c, const float lss = 0.1);

/**
* [pushArrowMarkerArray pushes marker to visualize arrows]
* @param marker_array [output marker array message]
* @param ls [input linestring]
* @param c [color of the marker]
*/
void pushArrowMarkerArray(
visualization_msgs::msg::MarkerArray * marker_array, const lanelet::ConstLineString3d & ls,
const std::string frame_id, const std::string ns, const std_msgs::msg::ColorRGBA c);

/**
* [initTrafficLightTriangleMarker initializes marker to visualize shape of traffic
* lights]
Expand Down
56 changes: 56 additions & 0 deletions map/lanelet2_extension/lib/visualization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#include "lanelet2_extension/utility/utilities.hpp"

#include <Eigen/Eigen>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/ros/marker_helper.hpp>

#include <visualization_msgs/msg/marker.hpp>
#include <visualization_msgs/msg/marker_array.hpp>
Expand Down Expand Up @@ -880,6 +882,7 @@ visualization_msgs::msg::MarkerArray visualization::laneletsBoundaryAsMarkerArra
std::unordered_set<lanelet::Id> added;
visualization_msgs::msg::Marker left_line_strip, right_line_strip, start_bound_line_strip,
center_line_strip;
visualization_msgs::msg::MarkerArray center_line_arrows;
visualization::initLineStringMarker(
&left_line_strip, "map", additional_namespace + "left_lane_bound", c);
visualization::initLineStringMarker(
Expand Down Expand Up @@ -915,6 +918,8 @@ visualization_msgs::msg::MarkerArray visualization::laneletsBoundaryAsMarkerArra
}
if (viz_centerline && !exists(added, center_ls.id())) {
visualization::pushLineStringMarker(&center_line_strip, center_ls, c, lss_center);
visualization::pushArrowMarkerArray(
&center_line_arrows, center_ls, "map", additional_namespace + "center_line_arrows", c);
added.insert(center_ls.id());
}
}
Expand All @@ -932,6 +937,9 @@ visualization_msgs::msg::MarkerArray visualization::laneletsBoundaryAsMarkerArra
if (!start_bound_line_strip.points.empty()) {
marker_array.markers.push_back(start_bound_line_strip);
}
marker_array.markers.insert(
marker_array.markers.end(), center_line_arrows.markers.begin(),
center_line_arrows.markers.end());
return marker_array;
}

Expand Down Expand Up @@ -1183,4 +1191,52 @@ void visualization::pushLineStringMarker(
}
}

void visualization::pushArrowMarkerArray(
visualization_msgs::msg::MarkerArray * marker_array, const lanelet::ConstLineString3d & ls,
const std::string frame_id, const std::string ns, const std_msgs::msg::ColorRGBA c)
{
if (marker_array == nullptr) {
RCLCPP_ERROR_STREAM(
rclcpp::get_logger("lanelet2_extension.visualization"),
__FUNCTION__ << ": marker_array is null pointer!");
return;
}

// fill out lane line
if (ls.size() < 2) {
RCLCPP_ERROR_STREAM(
rclcpp::get_logger("lanelet2_extension.visualization"),
__FUNCTION__ << ": marker line size is 1 or 0!");
return;
}

visualization_msgs::msg::Marker marker;
marker.header.frame_id = frame_id;
marker.header.stamp = rclcpp::Time();
marker.frame_locked = true;
marker.ns = ns;
marker.action = visualization_msgs::msg::Marker::ADD;
marker.type = visualization_msgs::msg::Marker::ARROW;

int32_t start_index = !marker_array->markers.empty() ? marker_array->markers.back().id : 0;
for (auto i = ls.begin(); i + 1 != ls.end(); i++) {
const auto index = i - ls.begin();
marker.id = start_index + index + 1;
const auto curr_point =
geometry_msgs::build<geometry_msgs::msg::Point>().x((*i).x()).y((*i).y()).z((*i).z());
const auto next_point = geometry_msgs::build<geometry_msgs::msg::Point>()
.x((*(i + 1)).x())
.y((*(i + 1)).y())
.z((*(i + 1)).z());
marker.pose.position = curr_point;

const double yaw = tier4_autoware_utils::calcAzimuthAngle(curr_point, next_point);
marker.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(yaw);
marker.scale = tier4_autoware_utils::createMarkerScale(0.3, 0.1, 0.1);
marker.color = c;

marker_array->markers.push_back(marker);
}
}

} // namespace lanelet

0 comments on commit e81d4e3

Please sign in to comment.