Skip to content

Commit

Permalink
can work now
Browse files Browse the repository at this point in the history
Signed-off-by: Berkay Karaman <[email protected]>

a

Signed-off-by: Berkay Karaman <[email protected]>
  • Loading branch information
brkay54 committed Sep 22, 2023
1 parent 442be04 commit 37c6cd5
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include <interpolation/linear_interpolation.hpp>
#include <motion_utils/trajectory/trajectory.hpp>
#include <tier4_autoware_utils/tier4_autoware_utils.hpp>
#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
Expand All @@ -26,6 +26,9 @@
#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/pose.hpp>

#include <boost/geometry/algorithms/convex_hull.hpp>
#include <boost/geometry/algorithms/correct.hpp>
#include <boost/geometry/algorithms/distance.hpp>
#include <boost/optional.hpp>

#include <map>
Expand All @@ -39,8 +42,6 @@ namespace utils
using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
using diagnostic_msgs::msg::DiagnosticStatus;
using diagnostic_msgs::msg::KeyValue;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::TransformStamped;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@

#include "predicted_path_checker/debug_marker.hpp"

#include <motion_utils/motion_utils.hpp>
#include <tier4_autoware_utils/tier4_autoware_utils.hpp>

#include <motion_utils/marker/marker_helper.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/ros/marker_helper.hpp>
#ifdef ROS_DISTRO_GALACTIC
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#include <tf2_eigen/tf2_eigen.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/math/unit_conversion.hpp>
#include <tier4_autoware_utils/ros/marker_helper.hpp>

#include <algorithm>
#include <memory>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,10 @@

#include "predicted_path_checker/utils.hpp"

#include <boost/format.hpp>
#include <boost/geometry/algorithms/convex_hull.hpp>
#include <boost/geometry/strategies/agnostic/hull_graham_andrew.hpp>

namespace utils
{

Expand Down

0 comments on commit 37c6cd5

Please sign in to comment.