|
| 1 | +// Copyright 2020 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 | +/* |
| 16 | + * Copyright 2018-2019 Autoware Foundation. All rights reserved. |
| 17 | + * |
| 18 | + * Licensed under the Apache License, Version 2.0 (the "License"); |
| 19 | + * you may not use this file except in compliance with the License. |
| 20 | + * You may obtain a copy of the License at |
| 21 | + * |
| 22 | + * http://www.apache.org/licenses/LICENSE-2.0 |
| 23 | + * |
| 24 | + * Unless required by applicable law or agreed to in writing, software |
| 25 | + * distributed under the License is distributed on an "AS IS" BASIS, |
| 26 | + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 27 | + * See the License for the specific language governing permissions and |
| 28 | + * limitations under the License. |
| 29 | + */ |
| 30 | + |
| 31 | +#ifndef FREESPACE_PLANNER__FREESPACE_PLANNER_NODE_HPP_ |
| 32 | +#define FREESPACE_PLANNER__FREESPACE_PLANNER_NODE_HPP_ |
| 33 | + |
| 34 | +#include <freespace_planning_algorithms/astar_search.hpp> |
| 35 | +#include <rclcpp/rclcpp.hpp> |
| 36 | +#include <vehicle_info_util/vehicle_info_util.hpp> |
| 37 | + |
| 38 | +#include <autoware_auto_planning_msgs/msg/had_map_route.hpp> |
| 39 | +#include <autoware_auto_planning_msgs/msg/trajectory.hpp> |
| 40 | +#include <autoware_planning_msgs/msg/scenario.hpp> |
| 41 | +#include <geometry_msgs/msg/twist.hpp> |
| 42 | +#include <nav_msgs/msg/occupancy_grid.hpp> |
| 43 | +#include <nav_msgs/msg/odometry.hpp> |
| 44 | + |
| 45 | +#include <tf2_geometry_msgs/tf2_geometry_msgs.h> |
| 46 | +#include <tf2_ros/buffer.h> |
| 47 | +#include <tf2_ros/transform_listener.h> |
| 48 | + |
| 49 | +#include <deque> |
| 50 | +#include <iostream> |
| 51 | +#include <memory> |
| 52 | +#include <string> |
| 53 | +#include <vector> |
| 54 | + |
| 55 | +namespace freespace_planner |
| 56 | +{ |
| 57 | +using autoware_auto_planning_msgs::msg::HADMapRoute; |
| 58 | +using autoware_auto_planning_msgs::msg::Trajectory; |
| 59 | +using autoware_planning_msgs::msg::Scenario; |
| 60 | +using freespace_planning_algorithms::AbstractPlanningAlgorithm; |
| 61 | +using freespace_planning_algorithms::AstarParam; |
| 62 | +using freespace_planning_algorithms::PlannerCommonParam; |
| 63 | +using geometry_msgs::msg::PoseArray; |
| 64 | +using geometry_msgs::msg::PoseStamped; |
| 65 | +using geometry_msgs::msg::TransformStamped; |
| 66 | +using geometry_msgs::msg::Twist; |
| 67 | +using nav_msgs::msg::OccupancyGrid; |
| 68 | +using nav_msgs::msg::Odometry; |
| 69 | + |
| 70 | +struct NodeParam |
| 71 | +{ |
| 72 | + std::string planning_algorithm; |
| 73 | + double waypoints_velocity; // constant velocity on planned waypoints [km/h] |
| 74 | + double update_rate; // replanning and publishing rate [Hz] |
| 75 | + double th_arrived_distance_m; |
| 76 | + double th_stopped_time_sec; |
| 77 | + double th_stopped_velocity_mps; |
| 78 | + double th_course_out_distance_m; |
| 79 | + bool replan_when_obstacle_found; |
| 80 | + bool replan_when_course_out; |
| 81 | +}; |
| 82 | + |
| 83 | +class FreespacePlannerNode : public rclcpp::Node |
| 84 | +{ |
| 85 | +public: |
| 86 | + explicit FreespacePlannerNode(const rclcpp::NodeOptions & node_options); |
| 87 | + |
| 88 | +private: |
| 89 | + // ros |
| 90 | + rclcpp::Publisher<Trajectory>::SharedPtr trajectory_pub_; |
| 91 | + rclcpp::Publisher<PoseArray>::SharedPtr debug_pose_array_pub_; |
| 92 | + rclcpp::Publisher<PoseArray>::SharedPtr debug_partial_pose_array_pub_; |
| 93 | + |
| 94 | + rclcpp::Subscription<HADMapRoute>::SharedPtr route_sub_; |
| 95 | + rclcpp::Subscription<OccupancyGrid>::SharedPtr occupancy_grid_sub_; |
| 96 | + rclcpp::Subscription<Scenario>::SharedPtr scenario_sub_; |
| 97 | + rclcpp::Subscription<Odometry>::SharedPtr odom_sub_; |
| 98 | + |
| 99 | + rclcpp::TimerBase::SharedPtr timer_; |
| 100 | + |
| 101 | + std::shared_ptr<tf2_ros::Buffer> tf_buffer_; |
| 102 | + std::shared_ptr<tf2_ros::TransformListener> tf_listener_; |
| 103 | + |
| 104 | + // params |
| 105 | + NodeParam node_param_; |
| 106 | + PlannerCommonParam planner_common_param_; |
| 107 | + AstarParam astar_param_; |
| 108 | + |
| 109 | + // variables |
| 110 | + std::unique_ptr<AbstractPlanningAlgorithm> algo_; |
| 111 | + PoseStamped current_pose_; |
| 112 | + PoseStamped goal_pose_; |
| 113 | + |
| 114 | + Trajectory trajectory_; |
| 115 | + Trajectory partial_trajectory_; |
| 116 | + std::vector<size_t> reversing_indices_; |
| 117 | + size_t prev_target_index_; |
| 118 | + size_t target_index_; |
| 119 | + bool is_completed_ = false; |
| 120 | + |
| 121 | + HADMapRoute::ConstSharedPtr route_; |
| 122 | + OccupancyGrid::ConstSharedPtr occupancy_grid_; |
| 123 | + Scenario::ConstSharedPtr scenario_; |
| 124 | + Odometry::ConstSharedPtr odom_; |
| 125 | + |
| 126 | + std::deque<Odometry::ConstSharedPtr> odom_buffer_; |
| 127 | + |
| 128 | + // functions used in the constructor |
| 129 | + void getPlanningCommonParam(); |
| 130 | + void getAstarParam(); |
| 131 | + |
| 132 | + // functions, callback |
| 133 | + void onRoute(const HADMapRoute::ConstSharedPtr msg); |
| 134 | + void onOccupancyGrid(const OccupancyGrid::ConstSharedPtr msg); |
| 135 | + void onScenario(const Scenario::ConstSharedPtr msg); |
| 136 | + void onOdometry(const Odometry::ConstSharedPtr msg); |
| 137 | + |
| 138 | + void onTimer(); |
| 139 | + |
| 140 | + void reset(); |
| 141 | + bool isPlanRequired(); |
| 142 | + void planTrajectory(); |
| 143 | + void updateTargetIndex(); |
| 144 | + void initializePlanningAlgorithm(); |
| 145 | + |
| 146 | + TransformStamped getTransform(const std::string & from, const std::string & to); |
| 147 | +}; |
| 148 | +} // namespace freespace_planner |
| 149 | + |
| 150 | +#endif // FREESPACE_PLANNER__FREESPACE_PLANNER_NODE_HPP_ |
0 commit comments