|
| 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 | +#ifndef AWAPI_AWIV_ADAPTER__AWAPI_AUTOWARE_UTIL_HPP_ |
| 16 | +#define AWAPI_AWIV_ADAPTER__AWAPI_AUTOWARE_UTIL_HPP_ |
| 17 | + |
| 18 | +#include <rclcpp/rclcpp.hpp> |
| 19 | + |
| 20 | +#include <autoware_api_msgs/msg/stop_command.hpp> |
| 21 | +#include <autoware_api_msgs/msg/velocity_limit.hpp> |
| 22 | +#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp> |
| 23 | +#include <autoware_auto_planning_msgs/msg/path.hpp> |
| 24 | +#include <autoware_auto_planning_msgs/msg/trajectory.hpp> |
| 25 | +#include <autoware_auto_system_msgs/msg/autoware_state.hpp> |
| 26 | +#include <autoware_auto_system_msgs/msg/emergency_state.hpp> |
| 27 | +#include <autoware_auto_system_msgs/msg/hazard_status_stamped.hpp> |
| 28 | +#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp> |
| 29 | +#include <autoware_auto_vehicle_msgs/msg/gear_report.hpp> |
| 30 | +#include <autoware_auto_vehicle_msgs/msg/hazard_lights_report.hpp> |
| 31 | +#include <autoware_auto_vehicle_msgs/msg/steering_report.hpp> |
| 32 | +#include <autoware_auto_vehicle_msgs/msg/turn_indicators_report.hpp> |
| 33 | +#include <autoware_control_msgs/msg/gate_mode.hpp> |
| 34 | +#include <autoware_planning_msgs/msg/is_avoidance_possible.hpp> |
| 35 | +#include <autoware_planning_msgs/msg/lane_change_status.hpp> |
| 36 | +#include <autoware_planning_msgs/msg/stop_reason_array.hpp> |
| 37 | +#include <autoware_planning_msgs/msg/velocity_limit.hpp> |
| 38 | +#include <autoware_v2x_msgs/msg/infrastructure_command_array.hpp> |
| 39 | +#include <autoware_v2x_msgs/msg/virtual_traffic_light_state_array.hpp> |
| 40 | +#include <autoware_vehicle_msgs/msg/battery_status.hpp> |
| 41 | +#include <diagnostic_msgs/msg/diagnostic_array.hpp> |
| 42 | +#include <geometry_msgs/msg/pose_stamped.hpp> |
| 43 | +#include <nav_msgs/msg/odometry.hpp> |
| 44 | +#include <pacmod3_msgs/msg/global_rpt.hpp> |
| 45 | +#include <pacmod3_msgs/msg/system_rpt_int.hpp> |
| 46 | +#include <sensor_msgs/msg/nav_sat_fix.hpp> |
| 47 | + |
| 48 | +#include <tf2/utils.h> |
| 49 | +#include <tf2_ros/transform_broadcaster.h> |
| 50 | +#include <tf2_ros/transform_listener.h> |
| 51 | + |
| 52 | +#include <memory> |
| 53 | +#include <string> |
| 54 | + |
| 55 | +namespace autoware_api |
| 56 | +{ |
| 57 | +struct AutowareInfo |
| 58 | +{ |
| 59 | + std::shared_ptr<geometry_msgs::msg::PoseStamped> current_pose_ptr; |
| 60 | + autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr steer_ptr; |
| 61 | + autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr vehicle_cmd_ptr; |
| 62 | + autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr turn_indicators_ptr; |
| 63 | + autoware_auto_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr hazard_lights_ptr; |
| 64 | + nav_msgs::msg::Odometry::ConstSharedPtr odometry_ptr; |
| 65 | + autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr gear_ptr; |
| 66 | + autoware_vehicle_msgs::msg::BatteryStatus::ConstSharedPtr battery_ptr; |
| 67 | + sensor_msgs::msg::NavSatFix::ConstSharedPtr nav_sat_ptr; |
| 68 | + autoware_auto_system_msgs::msg::AutowareState::ConstSharedPtr autoware_state_ptr; |
| 69 | + autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_ptr; |
| 70 | + autoware_control_msgs::msg::GateMode::ConstSharedPtr gate_mode_ptr; |
| 71 | + autoware_auto_system_msgs::msg::EmergencyState::ConstSharedPtr emergency_state_ptr; |
| 72 | + autoware_auto_system_msgs::msg::HazardStatusStamped::ConstSharedPtr hazard_status_ptr; |
| 73 | + autoware_planning_msgs::msg::StopReasonArray::ConstSharedPtr stop_reason_ptr; |
| 74 | + autoware_v2x_msgs::msg::InfrastructureCommandArray::ConstSharedPtr v2x_command_ptr; |
| 75 | + autoware_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr v2x_state_ptr; |
| 76 | + diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr diagnostic_ptr; |
| 77 | + pacmod3_msgs::msg::GlobalRpt::ConstSharedPtr global_rpt_ptr; |
| 78 | + autoware_planning_msgs::msg::LaneChangeStatus::ConstSharedPtr lane_change_available_ptr; |
| 79 | + autoware_planning_msgs::msg::LaneChangeStatus::ConstSharedPtr lane_change_ready_ptr; |
| 80 | + autoware_auto_planning_msgs::msg::Path::ConstSharedPtr lane_change_candidate_ptr; |
| 81 | + autoware_planning_msgs::msg::IsAvoidancePossible::ConstSharedPtr obstacle_avoid_ready_ptr; |
| 82 | + autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr obstacle_avoid_candidate_ptr; |
| 83 | + autoware_api_msgs::msg::VelocityLimit::ConstSharedPtr max_velocity_ptr; |
| 84 | + autoware_planning_msgs::msg::VelocityLimit::ConstSharedPtr current_max_velocity_ptr; |
| 85 | + autoware_api_msgs::msg::StopCommand::ConstSharedPtr temporary_stop_ptr; |
| 86 | + autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr autoware_planning_traj_ptr; |
| 87 | + pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr door_state_ptr; |
| 88 | +}; |
| 89 | + |
| 90 | +template <class T> |
| 91 | +T waitForParam( |
| 92 | + rclcpp::Node * node, const std::string & remote_node_name, const std::string & param_name) |
| 93 | +{ |
| 94 | + std::chrono::seconds sec(1); |
| 95 | + |
| 96 | + auto param_client = std::make_shared<rclcpp::SyncParametersClient>(node, remote_node_name); |
| 97 | + |
| 98 | + while (!param_client->wait_for_service(sec)) { |
| 99 | + if (!rclcpp::ok()) { |
| 100 | + RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service."); |
| 101 | + return {}; |
| 102 | + } |
| 103 | + RCLCPP_INFO_THROTTLE( |
| 104 | + node->get_logger(), *node->get_clock(), 1000 /* ms */, "waiting for node: %s, param: %s\n", |
| 105 | + remote_node_name.c_str(), param_name.c_str()); |
| 106 | + } |
| 107 | + |
| 108 | + if (param_client->has_parameter(param_name)) { |
| 109 | + return param_client->get_parameter<T>(param_name); |
| 110 | + } |
| 111 | + |
| 112 | + return {}; |
| 113 | +} |
| 114 | + |
| 115 | +double lowpass_filter(const double current_value, const double prev_value, const double gain); |
| 116 | + |
| 117 | +namespace planning_util |
| 118 | +{ |
| 119 | +bool calcClosestIndex( |
| 120 | + const autoware_auto_planning_msgs::msg::Trajectory & traj, const geometry_msgs::msg::Pose & pose, |
| 121 | + size_t & output_closest_idx, const double dist_thr = 10.0, const double angle_thr = M_PI / 2.0); |
| 122 | + |
| 123 | +inline geometry_msgs::msg::Pose getPose( |
| 124 | + const autoware_auto_planning_msgs::msg::Trajectory & traj, const int idx) |
| 125 | +{ |
| 126 | + return traj.points.at(idx).pose; |
| 127 | +} |
| 128 | + |
| 129 | +inline double calcDist2d(const geometry_msgs::msg::Point & a, const geometry_msgs::msg::Point & b) |
| 130 | +{ |
| 131 | + return std::hypot((a.x - b.x), (a.y - b.y)); |
| 132 | +} |
| 133 | + |
| 134 | +double normalizeEulerAngle(double euler); |
| 135 | + |
| 136 | +double calcArcLengthFromWayPoint( |
| 137 | + const autoware_auto_planning_msgs::msg::Trajectory & input_path, const size_t src_idx, |
| 138 | + const size_t dst_idx); |
| 139 | + |
| 140 | +double calcDistanceAlongTrajectory( |
| 141 | + const autoware_auto_planning_msgs::msg::Trajectory & trajectory, |
| 142 | + const geometry_msgs::msg::Pose & current_pose, const geometry_msgs::msg::Pose & target_pose); |
| 143 | + |
| 144 | +} // namespace planning_util |
| 145 | + |
| 146 | +} // namespace autoware_api |
| 147 | + |
| 148 | +#endif // AWAPI_AWIV_ADAPTER__AWAPI_AUTOWARE_UTIL_HPP_ |
0 commit comments