Autoware.Auto
|
|
calculate control command to follow reference waypoints More...
#include <mpc_trajectory.hpp>
Public Member Functions | |
void | push_back (const float64_t &xp, const float64_t &yp, const float64_t &zp, const float64_t &yawp, const float64_t &vxp, const float64_t &kp, const float64_t &smooth_kp, const float64_t &tp) |
push_back for all values More... | |
void | clear () |
clear for all values More... | |
size_t | size () const |
check size of MPCTrajectory More... | |
bool | empty () const |
Public Attributes | |
std::vector< float64_t > | x |
x position x vector More... | |
std::vector< float64_t > | y |
y position y vector More... | |
std::vector< float64_t > | z |
z position z vector More... | |
std::vector< float64_t > | yaw |
yaw pose yaw vector More... | |
std::vector< float64_t > | vx |
vx velocity vx vector More... | |
std::vector< float64_t > | k |
k curvature k vector More... | |
std::vector< float64_t > | smooth_k |
k smoothed-curvature k vector More... | |
std::vector< float64_t > | relative_time |
relative_time duration time from start point More... | |
calculate control command to follow reference waypoints
Trajectory class for mpc follower
void autoware::motion::control::trajectory_follower::MPCTrajectory::clear | ( | ) |
clear for all values
|
inline |
void autoware::motion::control::trajectory_follower::MPCTrajectory::push_back | ( | const float64_t & | xp, |
const float64_t & | yp, | ||
const float64_t & | zp, | ||
const float64_t & | yawp, | ||
const float64_t & | vxp, | ||
const float64_t & | kp, | ||
const float64_t & | smooth_kp, | ||
const float64_t & | tp | ||
) |
push_back for all values
size_t autoware::motion::control::trajectory_follower::MPCTrajectory::size | ( | ) | const |
check size of MPCTrajectory
std::vector<float64_t> autoware::motion::control::trajectory_follower::MPCTrajectory::k |
k curvature k vector
std::vector<float64_t> autoware::motion::control::trajectory_follower::MPCTrajectory::relative_time |
relative_time duration time from start point
std::vector<float64_t> autoware::motion::control::trajectory_follower::MPCTrajectory::smooth_k |
k smoothed-curvature k vector
std::vector<float64_t> autoware::motion::control::trajectory_follower::MPCTrajectory::vx |
vx velocity vx vector
std::vector<float64_t> autoware::motion::control::trajectory_follower::MPCTrajectory::x |
x position x vector
std::vector<float64_t> autoware::motion::control::trajectory_follower::MPCTrajectory::y |
y position y vector
std::vector<float64_t> autoware::motion::control::trajectory_follower::MPCTrajectory::yaw |
yaw pose yaw vector
std::vector<float64_t> autoware::motion::control::trajectory_follower::MPCTrajectory::z |
z position z vector