Autoware.Auto
trajectory_spoofer.hpp
Go to the documentation of this file.
1 // Copyright 2020 The Autoware Foundation
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 
18 
19 #ifndef TRAJECTORY_SPOOFER__TRAJECTORY_SPOOFER_HPP_
20 #define TRAJECTORY_SPOOFER__TRAJECTORY_SPOOFER_HPP_
21 
23 
24 #include <autoware_auto_msgs/msg/complex32.hpp>
25 #include <autoware_auto_msgs/msg/trajectory.hpp>
26 #include <autoware_auto_msgs/msg/trajectory_point.hpp>
27 #include <autoware_auto_msgs/msg/vehicle_kinematic_state.hpp>
28 #include <builtin_interfaces/msg/duration.hpp>
29 #include <common/types.hpp>
30 #include <rclcpp/duration.hpp>
31 #include <rclcpp/rclcpp.hpp>
32 
33 #include <chrono>
34 #include <cmath>
35 
36 namespace autoware
37 {
39 {
41 using DurationMsg = builtin_interfaces::msg::Duration;
45 
50 
51 
52 class TRAJECTORY_SPOOFER_PUBLIC TrajectorySpoofer
53 {
54  enum class CurveType
55  {
56  RIGHT_TURN = 0,
57  LEFT_TURN = 1
58  };
59 
60 private:
61  std::chrono::nanoseconds get_travel_time_ns(float32_t dist, float32_t speed);
62  Trajectory init_trajectory(
63  const VehicleKinematicState & starting_state,
64  TrajectoryPoint & first_point);
65 
66  float32_t target_speed_;
67 
68 public:
70  explicit TrajectorySpoofer(float32_t target_speed);
71 
72  static Complex32 to_2d_quaternion(float64_t yaw_angle);
73  static float64_t to_yaw_angle(const Complex32 & quat_2d);
74 
75  float32_t get_target_speed();
76  void set_target_speed(float32_t target_speed);
77 
78  Trajectory spoof_straight_trajectory(
79  const VehicleKinematicState & starting_point,
80  int32_t num_of_points,
81  float32_t length,
82  bool8_t speed_ramp_on = false);
83 
84  Trajectory spoof_circular_trajectory(
85  const VehicleKinematicState & starting_point,
86  int32_t num_of_points,
87  float32_t radius,
88  bool8_t speed_ramp_on = false);
89 
90  Trajectory spoof_curved_trajectory(
91  const VehicleKinematicState & starting_point,
92  int32_t num_of_points,
93  float32_t radius,
94  float32_t length,
95  CurveType mode = CurveType::RIGHT_TURN,
96  bool8_t speed_ramp_on = false);
97 };
98 } // namespace trajectory_spoofer
99 } // namespace autoware
100 
101 #endif // TRAJECTORY_SPOOFER__TRAJECTORY_SPOOFER_HPP_
autoware::trajectory_spoofer::VehicleKinematicState
autoware_auto_msgs::msg::VehicleKinematicState VehicleKinematicState
Definition: trajectory_spoofer.hpp:44
autoware::common::types::TAU
constexpr float32_t TAU
tau = 2 pi
Definition: types.hpp:54
types.hpp
This file includes common type definition.
visibility_control.hpp
autoware::trajectory_spoofer::TrajectorySpoofer
Definition: trajectory_spoofer.hpp:52
autoware::trajectory_spoofer::Complex32
autoware_auto_msgs::msg::Complex32 Complex32
Definition: trajectory_spoofer.hpp:40
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::trajectory_spoofer::DurationMsg
builtin_interfaces::msg::Duration DurationMsg
Definition: trajectory_spoofer.hpp:41
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
trajectory_spoofer
Definition: trajectory_spoofer.launch.py:1
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:47
autoware::trajectory_spoofer::Trajectory
autoware_auto_msgs::msg::Trajectory Trajectory
Definition: trajectory_spoofer.hpp:42
autoware::trajectory_spoofer::TrajectoryPoint
autoware_auto_msgs::msg::TrajectoryPoint TrajectoryPoint
Definition: trajectory_spoofer.hpp:43