Autoware.Auto
trajectory_smoother.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_SMOOTHER__TRAJECTORY_SMOOTHER_HPP_
20 #define TRAJECTORY_SMOOTHER__TRAJECTORY_SMOOTHER_HPP_
21 
22 #include "autoware_auto_planning_msgs/msg/trajectory.hpp"
23 #include <common/types.hpp>
24 #include <vector>
25 #include <cmath>
26 
28 
29 namespace motion
30 {
31 namespace planning
32 {
33 namespace trajectory_smoother
34 {
35 
38 
39 typedef struct
40 {
41  float32_t standard_deviation; // standard deviation of the gaussian kernel
42  uint32_t kernel_size; // length of the gaussian kernel
44 
45 
47 class TRAJECTORY_SMOOTHER_PUBLIC TrajectorySmoother
48 {
49 public:
53 
56  void Filter(Trajectory & trajectory);
57 
58 private:
59  std::vector<float32_t> m_kernel{};
60 };
61 
62 } // namespace trajectory_smoother
63 } // namespace planning
64 } // namespace motion
65 
66 #endif // TRAJECTORY_SMOOTHER__TRAJECTORY_SMOOTHER_HPP_
types.hpp
This file includes common type definition.
motion::planning::trajectory_smoother::TrajectorySmoother
Smooth over the trajectory by passing it through a gaussian filter.
Definition: trajectory_smoother.hpp:47
visibility_control.hpp
motion::planning::trajectory_smoother::TrajectorySmootherConfig::standard_deviation
float32_t standard_deviation
Definition: trajectory_smoother.hpp:41
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
motion
Definition: controller_base.hpp:31
motion::planning::trajectory_smoother::TrajectorySmootherConfig
Definition: trajectory_smoother.hpp:39
motion::motion_common::Trajectory
autoware_auto_planning_msgs::msg::Trajectory Trajectory
Definition: motion_common.hpp:41
motion::planning::trajectory_smoother::TrajectorySmootherConfig::kernel_size
uint32_t kernel_size
Definition: trajectory_smoother.hpp:42