Skip to content

Commit b076eb7

Browse files
authored
fix(surround_obstacle_checker): remove the virtual wall from the node (#5991)
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent e9d3a8e commit b076eb7

File tree

2 files changed

+0
-25
lines changed

2 files changed

+0
-25
lines changed

planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,6 @@ class SurroundObstacleCheckerDebugNode
7171
const double back_distance);
7272

7373
private:
74-
rclcpp::Publisher<MarkerArray>::SharedPtr debug_virtual_wall_pub_;
7574
rclcpp::Publisher<MarkerArray>::SharedPtr debug_viz_pub_;
7675
rclcpp::Publisher<StopReasonArray>::SharedPtr stop_reason_pub_;
7776
rclcpp::Publisher<VelocityFactorArray>::SharedPtr velocity_factor_pub_;
@@ -89,7 +88,6 @@ class SurroundObstacleCheckerDebugNode
8988
double surround_check_hysteresis_distance_;
9089
geometry_msgs::msg::Pose self_pose_;
9190

92-
MarkerArray makeVirtualWallMarker();
9391
MarkerArray makeVisualizationMarker();
9492
StopReasonArray makeStopReasonArray();
9593
VelocityFactorArray makeVelocityFactorArray();

planning/surround_obstacle_checker/src/debug_marker.cpp

-23
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,6 @@
1515
#include "surround_obstacle_checker/debug_marker.hpp"
1616

1717
#include <motion_utils/marker/marker_helper.hpp>
18-
#include <motion_utils/marker/virtual_wall_marker_creator.hpp>
1918
#include <tier4_autoware_utils/geometry/geometry.hpp>
2019
#include <tier4_autoware_utils/ros/marker_helper.hpp>
2120
#ifdef ROS_DISTRO_GALACTIC
@@ -52,7 +51,6 @@ Polygon2d createSelfPolygon(
5251
}
5352
} // namespace
5453

55-
using motion_utils::createStopVirtualWallMarker;
5654
using tier4_autoware_utils::appendMarkerArray;
5755
using tier4_autoware_utils::calcOffsetPose;
5856
using tier4_autoware_utils::createDefaultMarker;
@@ -76,8 +74,6 @@ SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode(
7674
self_pose_(self_pose),
7775
clock_(clock)
7876
{
79-
debug_virtual_wall_pub_ =
80-
node.create_publisher<visualization_msgs::msg::MarkerArray>("~/virtual_wall", 1);
8177
debug_viz_pub_ = node.create_publisher<visualization_msgs::msg::MarkerArray>("~/debug/marker", 1);
8278
stop_reason_pub_ = node.create_publisher<StopReasonArray>("~/output/stop_reasons", 1);
8379
velocity_factor_pub_ =
@@ -141,10 +137,6 @@ void SurroundObstacleCheckerDebugNode::publishFootprints()
141137

142138
void SurroundObstacleCheckerDebugNode::publish()
143139
{
144-
/* publish virtual_wall marker for rviz */
145-
const auto virtual_wall_msg = makeVirtualWallMarker();
146-
debug_virtual_wall_pub_->publish(virtual_wall_msg);
147-
148140
/* publish debug marker for rviz */
149141
const auto visualization_msg = makeVisualizationMarker();
150142
debug_viz_pub_->publish(visualization_msg);
@@ -160,21 +152,6 @@ void SurroundObstacleCheckerDebugNode::publish()
160152
stop_obstacle_point_ptr_ = nullptr;
161153
}
162154

163-
MarkerArray SurroundObstacleCheckerDebugNode::makeVirtualWallMarker()
164-
{
165-
MarkerArray msg;
166-
rclcpp::Time current_time = this->clock_->now();
167-
168-
// visualize stop line
169-
if (stop_pose_ptr_ != nullptr) {
170-
const auto p = calcOffsetPose(*stop_pose_ptr_, base_link2front_, 0.0, 0.0);
171-
const auto markers = createStopVirtualWallMarker(p, "surround obstacle", current_time, 0);
172-
appendMarkerArray(markers, &msg);
173-
}
174-
175-
return msg;
176-
}
177-
178155
MarkerArray SurroundObstacleCheckerDebugNode::makeVisualizationMarker()
179156
{
180157
MarkerArray msg;

0 commit comments

Comments
 (0)