|
| 1 | +// Copyright 2021 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_DEBUG_TOOLS__LATERAL_ERROR_PUBLISHER_HPP_ |
| 16 | +#define AUTOWARE_DEBUG_TOOLS__LATERAL_ERROR_PUBLISHER_HPP_ |
| 17 | + |
| 18 | +#define EIGEN_MPL2_ONLY |
| 19 | + |
| 20 | +#include <autoware_utils/trajectory/trajectory.hpp> |
| 21 | +#include <eigen3/Eigen/Core> |
| 22 | +#include <eigen3/Eigen/Geometry> |
| 23 | +#include <rclcpp/rclcpp.hpp> |
| 24 | + |
| 25 | +#include <autoware_auto_planning_msgs/msg/trajectory.hpp> |
| 26 | +#include <autoware_debug_msgs/msg/float32_stamped.hpp> |
| 27 | +#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp> |
| 28 | + |
| 29 | +class LateralErrorPublisher : public rclcpp::Node |
| 30 | +{ |
| 31 | +public: |
| 32 | + explicit LateralErrorPublisher(const rclcpp::NodeOptions & node_options); |
| 33 | + |
| 34 | +private: |
| 35 | + /* Parameters */ |
| 36 | + double yaw_threshold_to_search_closest_; |
| 37 | + |
| 38 | + /* States */ |
| 39 | + autoware_auto_planning_msgs::msg::Trajectory::SharedPtr |
| 40 | + current_trajectory_ptr_; //!< @brief reference trajectory |
| 41 | + geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr |
| 42 | + current_vehicle_pose_ptr_; //!< @brief current EKF pose |
| 43 | + geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr |
| 44 | + current_ground_truth_pose_ptr_; //!< @brief current GNSS pose |
| 45 | + |
| 46 | + /* Publishers and Subscribers */ |
| 47 | + rclcpp::Subscription<autoware_auto_planning_msgs::msg::Trajectory>::SharedPtr |
| 48 | + sub_trajectory_; //!< @brief subscription for reference trajectory |
| 49 | + rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr |
| 50 | + sub_vehicle_pose_; //!< @brief subscription for vehicle pose |
| 51 | + rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr |
| 52 | + sub_ground_truth_pose_; //!< @brief subscription for gnss pose |
| 53 | + rclcpp::Publisher<autoware_debug_msgs::msg::Float32Stamped>::SharedPtr |
| 54 | + pub_control_lateral_error_; //!< @brief publisher for control lateral error |
| 55 | + rclcpp::Publisher<autoware_debug_msgs::msg::Float32Stamped>::SharedPtr |
| 56 | + pub_localization_lateral_error_; //!< @brief publisher for localization lateral error |
| 57 | + rclcpp::Publisher<autoware_debug_msgs::msg::Float32Stamped>::SharedPtr |
| 58 | + pub_lateral_error_; //!< @brief publisher for lateral error (control + localization) |
| 59 | + |
| 60 | + /** |
| 61 | + * @brief set current_trajectory_ with received message |
| 62 | + */ |
| 63 | + void onTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr); |
| 64 | + /** |
| 65 | + * @brief set current_vehicle_pose_ with received message |
| 66 | + */ |
| 67 | + void onVehiclePose(const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); |
| 68 | + /** |
| 69 | + * @brief set current_ground_truth_pose_ and calculate lateral error |
| 70 | + */ |
| 71 | + void onGroundTruthPose(const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); |
| 72 | +}; |
| 73 | + |
| 74 | +#endif // AUTOWARE_DEBUG_TOOLS__LATERAL_ERROR_PUBLISHER_HPP_ |
0 commit comments