52 double estimateDeltaT(
const PoseSE2& start,
const PoseSE2& end,
53 double max_vel_x,
double max_vel_theta)
55 double dt_constant_motion = 0.1;
57 double trans_dist = (end.position() -
start.position()).norm();
58 dt_constant_motion = trans_dist / max_vel_x;
60 if (max_vel_theta > 0) {
61 double rot_dist = std::abs(g2o::normalize_theta(end.theta() -
start.theta()));
62 dt_constant_motion = std::max(dt_constant_motion, rot_dist / max_vel_theta);
64 return dt_constant_motion;
75 ROS_DEBUG(
"Destructor Timed_Elastic_Band...");
82 VertexPose* pose_vertex =
new VertexPose(pose, fixed);
89 VertexPose* pose_vertex =
new VertexPose(position, theta, fixed);
96 VertexPose* pose_vertex =
new VertexPose(x, y, theta, fixed);
103 ROS_ASSERT_MSG(dt > 0.,
"Adding a timediff requires a positive dt");
104 VertexTimeDiff* timediff_vertex =
new VertexTimeDiff(dt, fixed);
118 ROS_ERROR(
"Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
131 ROS_ERROR(
"Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
139 addPose(position, theta,
false);
142 ROS_ERROR(
"Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
157 for (
int i = index; i<index+number; ++i)
172 for (
int i = index; i<index+number; ++i)
204 for (PoseSequence::iterator pose_it =
pose_vec_.begin(); pose_it !=
pose_vec_.end(); ++pose_it)
231 bool modified =
true;
233 for (
int rep = 0; rep < 100 && modified; ++rep)
284 if (fast_mode)
break;
295 time += (*dt_it)->dt();
306 for(
int i = 0; i < index; ++i)
332 double timestep = 0.1;
337 double dir_to_goal = std::atan2(point_to_goal[1],point_to_goal[0]);
338 double dx = diststep*std::cos(dir_to_goal);
339 double dy = diststep*std::sin(dir_to_goal);
340 double orient_init = dir_to_goal;
342 if (guess_backwards_motion && point_to_goal.dot(
start.orientationUnitVec()) < 0)
343 orient_init = g2o::normalize_theta(orient_init+M_PI);
346 double dist_to_goal = point_to_goal.norm();
347 double no_steps_d = dist_to_goal/std::abs(diststep);
348 unsigned int no_steps = (
unsigned int) std::floor(no_steps_d);
350 if (max_vel_x > 0) timestep = diststep / max_vel_x;
352 for (
unsigned int i=1; i<=no_steps; i++)
354 if (i==no_steps && no_steps_d==(
float) no_steps)
364 ROS_DEBUG(
"initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
381 ROS_WARN(
"Cannot init TEB between given configuration and goal, because TEB vectors are not empty or TEB is already initialized (call this function before adding states yourself)!");
389 bool TimedElasticBand::initTrajectoryToGoal(
const std::vector<geometry_msgs::PoseStamped>& plan,
double max_vel_x,
double max_vel_theta,
bool estimate_orient,
int min_samples,
bool guess_backwards_motion)
394 PoseSE2
start(plan.front().pose);
395 PoseSE2 goal(plan.back().pose);
400 bool backwards =
false;
401 if (guess_backwards_motion && (goal.
position()-
start.position()).dot(
start.orientationUnitVec()) < 0)
405 for (
int i=1; i<(int)plan.size()-1; ++i)
411 double dx = plan[i+1].pose.position.x - plan[i].pose.position.x;
412 double dy = plan[i+1].pose.position.y - plan[i].pose.position.y;
413 yaw = std::atan2(dy,dx);
415 yaw = g2o::normalize_theta(yaw+M_PI);
421 PoseSE2 intermediate_pose(plan[i].pose.
position.x, plan[i].pose.position.y, yaw);
422 double dt = estimateDeltaT(
BackPose(), intermediate_pose, max_vel_x, max_vel_theta);
429 ROS_DEBUG(
"initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
434 double dt = estimateDeltaT(
BackPose(), intermediate_pose, max_vel_x, max_vel_theta);
440 double dt = estimateDeltaT(
BackPose(), goal, max_vel_x, max_vel_theta);
446 ROS_WARN(
"Cannot init TEB between given configuration and goal, because TEB vectors are not empty or TEB is already initialized (call this function before adding states yourself)!");
458 if (begin_idx < 0 || begin_idx >= n)
461 double min_dist_sq = std::numeric_limits<double>::max();
464 for (
int i = begin_idx; i < n; i++)
466 double dist_sq = (ref_point -
Pose(i).
position()).squaredNorm();
467 if (dist_sq < min_dist_sq)
469 min_dist_sq = dist_sq;
483 double min_dist = std::numeric_limits<double>::max();
511 double min_dist = std::numeric_limits<double>::max();
517 double dist_to_polygon = std::numeric_limits<double>::max();
518 for (
int j = 0; j < (int)
vertices.size()-1; ++j)
523 if (dist_to_polygon < min_dist)
525 min_dist = dist_to_polygon;
564 double dist_cache = (new_start->position()-
Pose(0).
position()).norm();
566 int lookahead = std::min<int>(
sizePoses()-min_samples, 10);
569 for (
int i = 1; i<=lookahead; ++i)
571 dist = (new_start->position()-
Pose(i).
position()).norm();
590 Pose(0) = *new_start;
605 double radius_sq = radius*radius;
606 double max_dist_behind_robot_sq = max_dist_behind_robot*max_dist_behind_robot;
609 for (
int i=1; i<
sizePoses(); i=i+skip_poses+1)
612 double dist_sq = dist_vec.squaredNorm();
614 if (dist_sq > radius_sq)
621 if (max_dist_behind_robot >= 0 && dist_vec.dot(robot_orient) < 0 && dist_sq > max_dist_behind_robot_sq)