|
| 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 DRIVING_ENVIRONMENT_ANALYZER__NODE_HPP_ |
| 16 | +#define DRIVING_ENVIRONMENT_ANALYZER__NODE_HPP_ |
| 17 | + |
| 18 | +#include "rosbag2_cpp/reader.hpp" |
| 19 | +#include "tier4_autoware_utils/ros/logger_level_configure.hpp" |
| 20 | + |
| 21 | +#include <route_handler/route_handler.hpp> |
| 22 | + |
| 23 | +#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp> |
| 24 | +#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp> |
| 25 | +#include <autoware_planning_msgs/msg/lanelet_route.hpp> |
| 26 | +#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp> |
| 27 | +#include <nav_msgs/msg/occupancy_grid.hpp> |
| 28 | +#include <nav_msgs/msg/odometry.hpp> |
| 29 | +#include <visualization_msgs/msg/marker.hpp> |
| 30 | + |
| 31 | +#include <map> |
| 32 | +#include <memory> |
| 33 | +#include <mutex> |
| 34 | +#include <string> |
| 35 | +#include <vector> |
| 36 | + |
| 37 | +namespace driving_environment_analyzer |
| 38 | +{ |
| 39 | +using autoware_auto_mapping_msgs::msg::HADMapBin; |
| 40 | +using autoware_auto_perception_msgs::msg::PredictedObject; |
| 41 | +using autoware_auto_perception_msgs::msg::PredictedObjects; |
| 42 | +using autoware_planning_msgs::msg::LaneletRoute; |
| 43 | +using geometry_msgs::msg::AccelWithCovarianceStamped; |
| 44 | +using nav_msgs::msg::Odometry; |
| 45 | + |
| 46 | +class DrivingEnvironmentAnalyzer : public rclcpp::Node |
| 47 | +{ |
| 48 | +public: |
| 49 | + explicit DrivingEnvironmentAnalyzer(const rclcpp::NodeOptions & node_options); |
| 50 | + |
| 51 | +private: |
| 52 | + bool isDataReady(const bool use_map_in_bag); |
| 53 | + void onMap(const HADMapBin::ConstSharedPtr map_msg); |
| 54 | + void analyze(); |
| 55 | + |
| 56 | + bool has_map_data_{false}; |
| 57 | + |
| 58 | + std::vector<LaneletRoute> route_msgs_; |
| 59 | + |
| 60 | + route_handler::RouteHandler route_handler_; |
| 61 | + LaneletRoute::ConstSharedPtr route_ptr_{nullptr}; |
| 62 | + rclcpp::Subscription<HADMapBin>::SharedPtr sub_map_; |
| 63 | + rclcpp::TimerBase::SharedPtr timer_; |
| 64 | + rosbag2_cpp::Reader reader_; |
| 65 | +}; |
| 66 | +} // namespace driving_environment_analyzer |
| 67 | + |
| 68 | +#endif // DRIVING_ENVIRONMENT_ANALYZER__NODE_HPP_ |
0 commit comments