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(surround_obstacle_checker)!: remove velocity factor #1737

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
1 change: 0 additions & 1 deletion planning/autoware_surround_obstacle_checker/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
<buildtool_depend>autoware_cmake</buildtool_depend>
<buildtool_depend>eigen3_cmake_module</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
Expand Down
23 changes: 0 additions & 23 deletions planning/autoware_surround_obstacle_checker/src/debug_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,8 +79,6 @@ SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode(
clock_(clock)
{
debug_viz_pub_ = node.create_publisher<visualization_msgs::msg::MarkerArray>("~/debug/marker", 1);
velocity_factor_pub_ =
node.create_publisher<VelocityFactorArray>("/planning/velocity_factors/surround_obstacle", 1);
vehicle_footprint_pub_ = node.create_publisher<PolygonStamped>("~/debug/footprint", 1);
vehicle_footprint_offset_pub_ =
node.create_publisher<PolygonStamped>("~/debug/footprint_offset", 1);
Expand Down Expand Up @@ -145,8 +143,6 @@ void SurroundObstacleCheckerDebugNode::publish()
debug_viz_pub_->publish(visualization_msg);

/* publish stop reason for autoware api */
const auto velocity_factor_msg = makeVelocityFactorArray();
velocity_factor_pub_->publish(velocity_factor_msg);
if (stop_pose_ptr_ != nullptr) {
planning_factor_interface_->add(
0.0, *stop_pose_ptr_, tier4_planning_msgs::msg::PlanningFactor::STOP,
Expand Down Expand Up @@ -178,25 +174,6 @@ MarkerArray SurroundObstacleCheckerDebugNode::makeVisualizationMarker()
return msg;
}

VelocityFactorArray SurroundObstacleCheckerDebugNode::makeVelocityFactorArray()
{
VelocityFactorArray velocity_factor_array;
velocity_factor_array.header.frame_id = "map";
velocity_factor_array.header.stamp = clock_->now();

if (stop_pose_ptr_) {
using distance_type = VelocityFactor::_distance_type;
VelocityFactor velocity_factor;
velocity_factor.behavior = PlanningBehavior::SURROUNDING_OBSTACLE;
velocity_factor.pose = *stop_pose_ptr_;
velocity_factor.distance = std::numeric_limits<distance_type>::quiet_NaN();
velocity_factor.status = VelocityFactor::UNKNOWN;
velocity_factor.detail = std::string();
velocity_factor_array.factors.push_back(velocity_factor);
}
return velocity_factor_array;
}

PolygonStamped SurroundObstacleCheckerDebugNode::boostPolygonToPolygonStamped(
const Polygon2d & boost_polygon, const double & z)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,6 @@
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_adapi_v1_msgs/msg/planning_behavior.hpp>
#include <autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp>
#include <geometry_msgs/msg/polygon_stamped.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <tier4_planning_msgs/msg/planning_factor_array.hpp>
Expand All @@ -36,9 +34,6 @@ namespace autoware::surround_obstacle_checker
{

using autoware::vehicle_info_utils::VehicleInfo;
using autoware_adapi_v1_msgs::msg::PlanningBehavior;
using autoware_adapi_v1_msgs::msg::VelocityFactor;
using autoware_adapi_v1_msgs::msg::VelocityFactorArray;
using geometry_msgs::msg::PolygonStamped;
using tier4_planning_msgs::msg::ControlPoint;
using tier4_planning_msgs::msg::PlanningFactor;
Expand Down Expand Up @@ -70,7 +65,6 @@ class SurroundObstacleCheckerDebugNode

private:
rclcpp::Publisher<MarkerArray>::SharedPtr debug_viz_pub_;
rclcpp::Publisher<VelocityFactorArray>::SharedPtr velocity_factor_pub_;

rclcpp::Publisher<PolygonStamped>::SharedPtr vehicle_footprint_pub_;
rclcpp::Publisher<PolygonStamped>::SharedPtr vehicle_footprint_offset_pub_;
Expand All @@ -87,7 +81,6 @@ class SurroundObstacleCheckerDebugNode
geometry_msgs::msg::Pose self_pose_;

MarkerArray makeVisualizationMarker();
VelocityFactorArray makeVelocityFactorArray();

PolygonStamped boostPolygonToPolygonStamped(const Polygon2d & boost_polygon, const double & z);

Expand Down
Loading