47 const Eigen::Vector3f& pos,
48 const Eigen::Vector3f& vel,
49 const Eigen::Vector3f& goal,
51 const Eigen::Vector3f& vsamples,
52 std::vector<Eigen::Vector3f> additional_samples,
53 bool discretize_by_time) {
54 initialise(pos, vel, goal, limits, vsamples, discretize_by_time);
61 const Eigen::Vector3f& pos,
62 const Eigen::Vector3f& vel,
63 const Eigen::Vector3f& goal,
65 const Eigen::Vector3f& vsamples,
66 bool discretize_by_time) {
71 double min_vel_th = -1.0 * max_vel_th;
86 if (vsamples[0] * vsamples[1] * vsamples[2] > 0) {
88 Eigen::Vector3f max_vel = Eigen::Vector3f::Zero();
89 Eigen::Vector3f min_vel = Eigen::Vector3f::Zero();
94 double dist = hypot(goal[0] - pos[0], goal[1] - pos[1]);
95 max_vel_x = std::max(std::min(max_vel_x, dist /
sim_time_), min_vel_x);
96 max_vel_y = std::max(std::min(max_vel_y, dist /
sim_time_), min_vel_y);
99 max_vel[0] = std::min(max_vel_x, vel[0] + acc_lim[0] *
sim_time_);
100 max_vel[1] = std::min(max_vel_y, vel[1] + acc_lim[1] *
sim_time_);
101 max_vel[2] = std::min(max_vel_th, vel[2] + acc_lim[2] *
sim_time_);
103 min_vel[0] = std::max(min_vel_x, vel[0] - acc_lim[0] *
sim_time_);
104 min_vel[1] = std::max(min_vel_y, vel[1] - acc_lim[1] *
sim_time_);
105 min_vel[2] = std::max(min_vel_th, vel[2] - acc_lim[2] *
sim_time_);
108 max_vel[0] = std::min(max_vel_x, vel[0] + acc_lim[0] *
sim_period_);
109 max_vel[1] = std::min(max_vel_y, vel[1] + acc_lim[1] *
sim_period_);
110 max_vel[2] = std::min(max_vel_th, vel[2] + acc_lim[2] *
sim_period_);
112 min_vel[0] = std::max(min_vel_x, vel[0] - acc_lim[0] *
sim_period_);
113 min_vel[1] = std::max(min_vel_y, vel[1] - acc_lim[1] *
sim_period_);
114 min_vel[2] = std::max(min_vel_th, vel[2] - acc_lim[2] *
sim_period_);
117 Eigen::Vector3f vel_samp = Eigen::Vector3f::Zero();
118 VelocityIterator x_it(min_vel[0], max_vel[0], vsamples[0]);
119 VelocityIterator y_it(min_vel[1], max_vel[1], vsamples[1]);
120 VelocityIterator th_it(min_vel[2], max_vel[2], vsamples[2]);
121 for(; !x_it.isFinished(); x_it++) {
122 vel_samp[0] = x_it.getVelocity();
123 for(; !y_it.isFinished(); y_it++) {
124 vel_samp[1] = y_it.getVelocity();
125 for(; !th_it.isFinished(); th_it++) {
126 vel_samp[2] = th_it.getVelocity();
139 double sim_granularity,
140 double angular_sim_granularity,
183 Eigen::Vector3f sample_target_vel,
185 double vmag = hypot(sample_target_vel[0], sample_target_vel[1]);
207 double sim_time_distance = vmag *
sim_time_;
208 double sim_time_angle = fabs(sample_target_vel[2]) *
sim_time_;
214 if (num_steps == 0) {
222 Eigen::Vector3f loop_vel;
226 traj.
xv_ = loop_vel[0];
227 traj.
yv_ = loop_vel[1];
231 loop_vel = sample_target_vel;
232 traj.
xv_ = sample_target_vel[0];
233 traj.
yv_ = sample_target_vel[1];
234 traj.
thetav_ = sample_target_vel[2];
238 for (
int i = 0; i < num_steps; ++i) {
241 traj.
addPoint(pos[0], pos[1], pos[2]);
258 const Eigen::Vector3f& vel,
double dt) {
259 Eigen::Vector3f new_pos = Eigen::Vector3f::Zero();
260 new_pos[0] = pos[0] + (vel[0] * cos(pos[2]) + vel[1] * cos(M_PI_2 + pos[2])) * dt;
261 new_pos[1] = pos[1] + (vel[0] * sin(pos[2]) + vel[1] * sin(M_PI_2 + pos[2])) * dt;
262 new_pos[2] = pos[2] + vel[2] * dt;
270 const Eigen::Vector3f& vel, Eigen::Vector3f acclimits,
double dt) {
271 Eigen::Vector3f new_vel = Eigen::Vector3f::Zero();
272 for (
int i = 0; i < 3; ++i) {
273 if (vel[i] < sample_target_vel[i]) {
274 new_vel[i] = std::min(
double(sample_target_vel[i]), vel[i] + acclimits[i] * dt);
276 new_vel[i] = std::max(
double(sample_target_vel[i]), vel[i] - acclimits[i] * dt);