Autoware.Auto
trajectory_spoofer_node.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_NODE_HPP_
20 #define TRAJECTORY_SPOOFER__TRAJECTORY_SPOOFER_NODE_HPP_
21 
23 
24 #include <autoware_auto_msgs/msg/vehicle_kinematic_state.hpp>
25 #include <autoware_auto_msgs/msg/trajectory.hpp>
26 #include <common/types.hpp>
27 #include <rclcpp/rclcpp.hpp>
28 
29 #include <memory>
30 #include <string>
31 
32 namespace autoware
33 {
34 namespace trajectory_spoofer
35 {
38 using std::placeholders::_1;
39 
42 class TRAJECTORY_SPOOFER_PUBLIC TrajectorySpooferNode
43  : public rclcpp::Node
44 {
45 private:
46  enum class TrajectoryType : uint8_t
47  {
48  STRAIGHT = 1u,
49  CIRCLE = 2u,
50  };
51 
52  bool8_t speed_ramp_on_;
53  float32_t target_speed_;
54  int32_t num_of_points_;
55  TrajectoryType trajectory_type_;
56  float32_t length_;
57  float32_t radius_;
58 
59  Trajectory trajectory_;
60 
61  std::shared_ptr<TrajectorySpoofer> spoofer_;
62  std::shared_ptr<rclcpp::Publisher<Trajectory>> trajectory_pub_;
63  std::shared_ptr<rclcpp::Subscription<VehicleKinematicState>> state_sub_;
64 
65  TrajectoryType get_trajectory_type_from_string(const std::string & trajectory_type_string)
66  {
67  if (trajectory_type_string == "straight") {
68  return TrajectoryType::STRAIGHT;
69  } else if (trajectory_type_string == "circle") {
70  return TrajectoryType::CIRCLE;
71  } else {
72  throw std::invalid_argument{"Unknown trajectory type"};
73  }
74  }
75 
76 public:
80  explicit TrajectorySpooferNode(const rclcpp::NodeOptions & node_options);
81 
82  void on_recv_state(VehicleKinematicState::SharedPtr msg);
83 };
84 
85 } // namespace trajectory_spoofer
86 } // namespace autoware
87 
88 #endif // TRAJECTORY_SPOOFER__TRAJECTORY_SPOOFER_NODE_HPP_
autoware::trajectory_spoofer::VehicleKinematicState
autoware_auto_msgs::msg::VehicleKinematicState VehicleKinematicState
Definition: trajectory_spoofer.hpp:44
types.hpp
This file includes common type definition.
trajectory_spoofer.hpp
This file defines the TrajectorySpoofer class.
u
DifferentialState u
Definition: kinematic_bicycle.snippet.hpp:29
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::TrajectorySpooferNode
ROS 2 Node for creating fake trajectories.
Definition: trajectory_spoofer_node.hpp:42
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
trajectory_spoofer
Definition: trajectory_spoofer.launch.py:1
autoware::trajectory_spoofer::Trajectory
autoware_auto_msgs::msg::Trajectory Trajectory
Definition: trajectory_spoofer.hpp:42
motion::motion_common::Trajectory
autoware_auto_msgs::msg::Trajectory Trajectory
Definition: motion_common.hpp:37