Skip to content

Commit

Permalink
feat(lanalet2_extension): set frame_locked to false (autowarefoundati…
Browse files Browse the repository at this point in the history
…on#153)

Signed-off-by: tomoya.kimura <[email protected]>
  • Loading branch information
tkimura4 authored Feb 6, 2023
1 parent 042cbf3 commit e1e46ca
Showing 1 changed file with 12 additions and 12 deletions.
24 changes: 12 additions & 12 deletions tmp/lanelet2_extension/lib/visualization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ void initLightMarker(visualization_msgs::msg::Marker * marker, const std::string

marker->header.frame_id = "map";
marker->header.stamp = rclcpp::Time();
marker->frame_locked = true;
marker->frame_locked = false;
marker->ns = ns;
marker->id = 0;
marker->lifetime = rclcpp::Duration(0, 0);
Expand Down Expand Up @@ -156,7 +156,7 @@ void initLaneletDirectionMarker(visualization_msgs::msg::Marker * marker, const

marker->header.frame_id = "map";
marker->header.stamp = rclcpp::Time();
marker->frame_locked = true;
marker->frame_locked = false;
marker->ns = ns;
marker->id = 0;
marker->type = visualization_msgs::msg::Marker::TRIANGLE_LIST;
Expand Down Expand Up @@ -293,7 +293,7 @@ visualization_msgs::msg::Marker createPolygonMarker(
visualization_msgs::msg::Marker marker;
marker.header.frame_id = "map";
marker.header.stamp = rclcpp::Time();
marker.frame_locked = true;
marker.frame_locked = false;
marker.id = 0;
marker.ns = name_space;
marker.type = visualization_msgs::msg::Marker::TRIANGLE_LIST;
Expand Down Expand Up @@ -565,7 +565,7 @@ visualization_msgs::msg::MarkerArray visualization::generateTrafficLightIdMaker(
marker.pose.orientation.w = 1.0;
marker.color = c;
marker.scale.z = scale;
marker.frame_locked = true;
marker.frame_locked = false;
marker.text = std::to_string(ls.id());
tl_id_marker_array.markers.push_back(marker);
}
Expand All @@ -589,7 +589,7 @@ visualization_msgs::msg::MarkerArray visualization::detectionAreasAsMarkerArray(

marker.header.frame_id = "map";
marker.header.stamp = rclcpp::Time();
marker.frame_locked = true;
marker.frame_locked = false;
marker.ns = "detection_area";
marker.id = 0;
marker.type = visualization_msgs::msg::Marker::TRIANGLE_LIST;
Expand Down Expand Up @@ -664,7 +664,7 @@ visualization_msgs::msg::MarkerArray visualization::noStoppingAreasAsMarkerArray

marker.header.frame_id = "map";
marker.header.stamp = rclcpp::Time();
marker.frame_locked = true;
marker.frame_locked = false;
marker.ns = "no_stopping_area";
marker.id = 0;
marker.type = visualization_msgs::msg::Marker::TRIANGLE_LIST;
Expand Down Expand Up @@ -742,7 +742,7 @@ visualization_msgs::msg::MarkerArray visualization::speedBumpsAsMarkerArray(

marker.header.frame_id = "map";
marker.header.stamp = rclcpp::Time();
marker.frame_locked = true;
marker.frame_locked = false;
marker.ns = "speed_bump";
marker.id = 0;
marker.type = visualization_msgs::msg::Marker::TRIANGLE_LIST;
Expand Down Expand Up @@ -885,7 +885,7 @@ visualization_msgs::msg::MarkerArray visualization::generateLaneletIdMarker(
marker.pose.orientation.w = 1.0;
marker.color = c;
marker.scale.z = scale;
marker.frame_locked = true;
marker.frame_locked = false;
marker.text = std::to_string(ll.id());
markers.markers.push_back(marker);
}
Expand Down Expand Up @@ -1046,7 +1046,7 @@ visualization_msgs::msg::MarkerArray visualization::laneletsAsTriangleMarkerArra

marker.header.frame_id = "map";
marker.header.stamp = rclcpp::Time();
marker.frame_locked = true;
marker.frame_locked = false;
marker.ns = ns;
marker.id = 0;
marker.type = visualization_msgs::msg::Marker::TRIANGLE_LIST;
Expand Down Expand Up @@ -1099,7 +1099,7 @@ void visualization::initTrafficLightTriangleMarker(

marker->header.frame_id = "map";
marker->header.stamp = rclcpp::Time();
marker->frame_locked = true;
marker->frame_locked = false;
marker->ns = ns;
marker->id = 0;
marker->type = visualization_msgs::msg::Marker::TRIANGLE_LIST;
Expand Down Expand Up @@ -1184,7 +1184,7 @@ void visualization::initLineStringMarker(

marker->header.frame_id = frame_id;
marker->header.stamp = rclcpp::Time();
marker->frame_locked = true;
marker->frame_locked = false;
marker->ns = ns;
marker->action = visualization_msgs::msg::Marker::ADD;
marker->type = visualization_msgs::msg::Marker::TRIANGLE_LIST;
Expand Down Expand Up @@ -1268,7 +1268,7 @@ void visualization::initArrowsMarker(

marker->header.frame_id = frame_id;
marker->header.stamp = rclcpp::Time();
marker->frame_locked = true;
marker->frame_locked = false;
marker->ns = ns;
marker->action = visualization_msgs::msg::Marker::ADD;
marker->type = visualization_msgs::msg::Marker::TRIANGLE_LIST;
Expand Down

0 comments on commit e1e46ca

Please sign in to comment.