|
| 1 | +// Copyright 2024 TIER IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#ifndef AUTOWARE__FREESPACE_PLANNER__UTILS_HPP_ |
| 16 | +#define AUTOWARE__FREESPACE_PLANNER__UTILS_HPP_ |
| 17 | + |
| 18 | +#include "autoware/freespace_planning_algorithms/abstract_algorithm.hpp" |
| 19 | + |
| 20 | +#include <rclcpp/rclcpp.hpp> |
| 21 | + |
| 22 | +#include <autoware_planning_msgs/msg/trajectory.hpp> |
| 23 | +#include <autoware_planning_msgs/msg/trajectory_point.hpp> |
| 24 | +#include <geometry_msgs/msg/pose_array.hpp> |
| 25 | +#include <geometry_msgs/msg/pose_stamped.hpp> |
| 26 | +#include <geometry_msgs/msg/transform_stamped.hpp> |
| 27 | +#include <nav_msgs/msg/odometry.hpp> |
| 28 | +#include <tier4_planning_msgs/msg/scenario.hpp> |
| 29 | + |
| 30 | +#include <deque> |
| 31 | +#include <vector> |
| 32 | + |
| 33 | +namespace autoware::freespace_planner::utils |
| 34 | +{ |
| 35 | +using autoware::freespace_planning_algorithms::PlannerWaypoint; |
| 36 | +using autoware::freespace_planning_algorithms::PlannerWaypoints; |
| 37 | +using autoware_planning_msgs::msg::Trajectory; |
| 38 | +using autoware_planning_msgs::msg::TrajectoryPoint; |
| 39 | +using geometry_msgs::msg::Pose; |
| 40 | +using geometry_msgs::msg::PoseArray; |
| 41 | +using geometry_msgs::msg::PoseStamped; |
| 42 | +using geometry_msgs::msg::TransformStamped; |
| 43 | +using nav_msgs::msg::Odometry; |
| 44 | +using tier4_planning_msgs::msg::Scenario; |
| 45 | + |
| 46 | +PoseArray trajectory_to_pose_array(const Trajectory & trajectory); |
| 47 | + |
| 48 | +double calc_distance_2d(const Trajectory & trajectory, const Pose & pose); |
| 49 | + |
| 50 | +Pose transform_pose(const Pose & pose, const TransformStamped & transform); |
| 51 | + |
| 52 | +bool is_active(const Scenario::ConstSharedPtr & scenario); |
| 53 | + |
| 54 | +std::vector<size_t> get_reversing_indices(const Trajectory & trajectory); |
| 55 | + |
| 56 | +size_t get_next_target_index( |
| 57 | + const size_t trajectory_size, const std::vector<size_t> & reversing_indices, |
| 58 | + const size_t current_target_index); |
| 59 | + |
| 60 | +Trajectory get_partial_trajectory( |
| 61 | + const Trajectory & trajectory, const size_t start_index, const size_t end_index); |
| 62 | + |
| 63 | +Trajectory create_trajectory( |
| 64 | + const PoseStamped & current_pose, const PlannerWaypoints & planner_waypoints, |
| 65 | + const double & velocity); |
| 66 | + |
| 67 | +Trajectory create_stop_trajectory(const PoseStamped & current_pose); |
| 68 | + |
| 69 | +Trajectory create_stop_trajectory(const Trajectory & trajectory); |
| 70 | + |
| 71 | +bool is_stopped( |
| 72 | + const std::deque<Odometry::ConstSharedPtr> & odom_buffer, const double th_stopped_velocity_mps); |
| 73 | + |
| 74 | +bool is_near_target( |
| 75 | + const Pose & target_pose, const Pose & current_pose, const double th_distance_m); |
| 76 | +} // namespace autoware::freespace_planner::utils |
| 77 | + |
| 78 | +#endif // AUTOWARE__FREESPACE_PLANNER__UTILS_HPP_ |
0 commit comments