Autoware.Auto
mpc_trajectory.hpp
Go to the documentation of this file.
1 // Copyright 2018-2021 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 
15 #ifndef TRAJECTORY_FOLLOWER__MPC_TRAJECTORY_HPP_
16 #define TRAJECTORY_FOLLOWER__MPC_TRAJECTORY_HPP_
17 
18 #include <iostream>
19 #include <vector>
20 
21 #include "common/types.hpp"
23 
24 namespace autoware
25 {
26 namespace motion
27 {
28 namespace control
29 {
30 namespace trajectory_follower
31 {
37 class TRAJECTORY_FOLLOWER_PUBLIC MPCTrajectory
38 {
39 public:
40  std::vector<float64_t> x;
41  std::vector<float64_t> y;
42  std::vector<float64_t> z;
43  std::vector<float64_t> yaw;
44  std::vector<float64_t> vx;
45  std::vector<float64_t> k;
46  std::vector<float64_t> smooth_k;
47  std::vector<float64_t> relative_time;
48 
52  void push_back(
53  const float64_t & xp, const float64_t & yp, const float64_t & zp, const float64_t & yawp,
54  const float64_t & vxp, const float64_t & kp, const float64_t & smooth_kp, const float64_t & tp);
58  void clear();
59 
64  size_t size() const;
68  inline bool empty() const
69  {
70  return size() == 0;
71  }
72 };
73 } // namespace trajectory_follower
74 } // namespace control
75 } // namespace motion
76 } // namespace autoware
77 #endif // TRAJECTORY_FOLLOWER__MPC_TRAJECTORY_HPP_
autoware::motion::control::trajectory_follower::MPCTrajectory::y
std::vector< float64_t > y
y position y vector
Definition: mpc_trajectory.hpp:41
autoware::motion::control::trajectory_follower::MPCTrajectory::yaw
std::vector< float64_t > yaw
yaw pose yaw vector
Definition: mpc_trajectory.hpp:43
visibility_control.hpp
autoware::motion::control::trajectory_follower::MPCTrajectory::vx
std::vector< float64_t > vx
vx velocity vx vector
Definition: mpc_trajectory.hpp:44
types.hpp
This file includes common type definition.
autoware::motion::control::trajectory_follower::MPCTrajectory::x
std::vector< float64_t > x
x position x vector
Definition: mpc_trajectory.hpp:40
autoware::motion::control::trajectory_follower::MPCTrajectory::smooth_k
std::vector< float64_t > smooth_k
k smoothed-curvature k vector
Definition: mpc_trajectory.hpp:46
autoware::motion::control::trajectory_follower::MPCTrajectory::relative_time
std::vector< float64_t > relative_time
relative_time duration time from start point
Definition: mpc_trajectory.hpp:47
autoware::motion::control::trajectory_follower::MPCTrajectory::empty
bool empty() const
Definition: mpc_trajectory.hpp:68
autoware::motion::control::trajectory_follower::MPCTrajectory::z
std::vector< float64_t > z
z position z vector
Definition: mpc_trajectory.hpp:42
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::motion::control::trajectory_follower
Definition: debug_values.hpp:29
motion
Definition: controller_base.hpp:31
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:47
autoware::motion::control::trajectory_follower::MPCTrajectory::k
std::vector< float64_t > k
k curvature k vector
Definition: mpc_trajectory.hpp:45
autoware::motion::control::trajectory_follower::MPCTrajectory
calculate control command to follow reference waypoints
Definition: mpc_trajectory.hpp:37