Go to the documentation of this file.
15 #ifndef TRAJECTORY_FOLLOWER__MPC_TRAJECTORY_HPP_
16 #define TRAJECTORY_FOLLOWER__MPC_TRAJECTORY_HPP_
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;
77 #endif // TRAJECTORY_FOLLOWER__MPC_TRAJECTORY_HPP_
std::vector< float64_t > y
y position y vector
Definition: mpc_trajectory.hpp:41
std::vector< float64_t > yaw
yaw pose yaw vector
Definition: mpc_trajectory.hpp:43
std::vector< float64_t > vx
vx velocity vx vector
Definition: mpc_trajectory.hpp:44
This file includes common type definition.
std::vector< float64_t > x
x position x vector
Definition: mpc_trajectory.hpp:40
std::vector< float64_t > smooth_k
k smoothed-curvature k vector
Definition: mpc_trajectory.hpp:46
std::vector< float64_t > relative_time
relative_time duration time from start point
Definition: mpc_trajectory.hpp:47
bool empty() const
Definition: mpc_trajectory.hpp:68
std::vector< float64_t > z
z position z vector
Definition: mpc_trajectory.hpp:42
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Definition: debug_values.hpp:29
Definition: controller_base.hpp:31
double float64_t
Definition: types.hpp:47
std::vector< float64_t > k
k curvature k vector
Definition: mpc_trajectory.hpp:45
calculate control command to follow reference waypoints
Definition: mpc_trajectory.hpp:37