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

feat(surrround_obstacle_checker): use planning factor #1717

Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,9 @@ SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode(
const double & surround_check_back_distance, const double & surround_check_hysteresis_distance,
const geometry_msgs::msg::Pose & self_pose, const rclcpp::Clock::SharedPtr clock,
rclcpp::Node & node)
: vehicle_info_(vehicle_info),
: planning_factor_interface_{std::make_unique<autoware::motion_utils::PlanningFactorInterface>(
&node, "surround_obstacle_checker")},
vehicle_info_(vehicle_info),
object_label_(object_label),
surround_check_front_distance_(surround_check_front_distance),
surround_check_side_distance_(surround_check_side_distance),
Expand Down Expand Up @@ -145,6 +147,12 @@ void SurroundObstacleCheckerDebugNode::publish()
/* 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,
tier4_planning_msgs::msg::SafetyFactorArray{});
}
planning_factor_interface_->publish();

/* reset variables */
stop_pose_ptr_ = nullptr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,13 +15,15 @@
#ifndef DEBUG_MARKER_HPP_
#define DEBUG_MARKER_HPP_

#include <autoware/motion_utils/factor/planning_factor_interface.hpp>
#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>
#include <visualization_msgs/msg/marker.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

Expand All @@ -38,6 +40,9 @@ 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;
using tier4_planning_msgs::msg::PlanningFactorArray;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;

Expand Down Expand Up @@ -71,6 +76,8 @@ class SurroundObstacleCheckerDebugNode
rclcpp::Publisher<PolygonStamped>::SharedPtr vehicle_footprint_offset_pub_;
rclcpp::Publisher<PolygonStamped>::SharedPtr vehicle_footprint_recover_offset_pub_;

std::unique_ptr<autoware::motion_utils::PlanningFactorInterface> planning_factor_interface_;

autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
std::string object_label_;
double surround_check_front_distance_;
Expand Down
Loading