52 ROS_DEBUG(
"Destructor Timed_Elastic_Band...");
94 ROS_ERROR(
"Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
107 ROS_ERROR(
"Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
115 addPose(position, theta,
false);
118 ROS_ERROR(
"Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf");
133 for (
int i = index; i<index+number; ++i)
148 for (
int i = index; i<index+number; ++i)
180 for (PoseSequence::iterator pose_it =
pose_vec_.begin(); pose_it !=
pose_vec_.end(); ++pose_it)
207 bool modified =
true;
209 for (
int rep = 0; rep < 100 && modified; ++rep)
247 if (fast_mode)
break;
258 time += (*dt_it)->dt();
269 for(
int i = 0; i < index; ++i)
295 double timestep = 0.1;
300 double dir_to_goal = std::atan2(point_to_goal[1],point_to_goal[0]);
301 double dx = diststep*std::cos(dir_to_goal);
302 double dy = diststep*std::sin(dir_to_goal);
303 double orient_init = dir_to_goal;
306 orient_init = g2o::normalize_theta(orient_init+M_PI);
309 double dist_to_goal = point_to_goal.norm();
310 double no_steps_d = dist_to_goal/std::abs(diststep);
311 unsigned int no_steps = (
unsigned int) std::floor(no_steps_d);
313 if (max_vel_x > 0) timestep = diststep / max_vel_x;
315 for (
unsigned int i=1; i<=no_steps; i++)
317 if (i==no_steps && no_steps_d==(
float) no_steps)
327 ROS_DEBUG(
"initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
344 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)!");
357 PoseSE2 start(plan.front().pose);
358 PoseSE2 goal(plan.back().pose);
365 bool backwards =
false;
366 if (guess_backwards_motion && (goal.position()-start.position()).
dot(start.orientationUnitVec()) < 0)
370 for (
int i=1; i<(int)plan.size()-1; ++i)
376 double dx = plan[i+1].pose.position.x - plan[i].pose.position.x;
377 double dy = plan[i+1].pose.position.y - plan[i].pose.position.y;
378 yaw = std::atan2(dy,dx);
380 yaw = g2o::normalize_theta(yaw+M_PI);
386 PoseSE2 intermediate_pose(plan[i].pose.position.x, plan[i].pose.position.y, yaw);
394 ROS_DEBUG(
"initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
405 if (max_vel_x > 0) dt = (goal.position()-
BackPose().
position()).norm()/max_vel_x;
411 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)!");
422 std::vector<double> dist_vec;
428 for (
int i = begin_idx; i < n; i++)
431 dist_vec.push_back(diff.norm());
434 if (dist_vec.empty())
440 double last_value = dist_vec.at(0);
441 for (
int i=1; i < (int)dist_vec.size(); i++)
443 if (dist_vec.at(i) < last_value)
445 last_value = dist_vec.at(i);
450 *distance = last_value;
451 return begin_idx+index_min;
457 std::vector<double> dist_vec;
463 for (
int i = 0; i < n; i++)
467 dist_vec.push_back(diff);
470 if (dist_vec.empty())
476 double last_value = dist_vec.at(0);
477 for (
int i=1; i < (int)dist_vec.size(); i++)
479 if (dist_vec.at(i) < last_value)
481 last_value = dist_vec.at(i);
486 *distance = last_value;
492 if (vertices.empty())
494 else if (vertices.size() == 1)
496 else if (vertices.size() == 2)
499 std::vector<double> dist_vec;
505 for (
int i = 0; i < n; i++)
508 double diff = HUGE_VAL;
509 for (
int j = 0; j < (int) vertices.size()-1; ++j)
514 dist_vec.push_back(diff);
517 if (dist_vec.empty())
523 double last_value = dist_vec.at(0);
524 for (
int i=1; i < (int)dist_vec.size(); i++)
526 if (dist_vec.at(i) < last_value)
528 last_value = dist_vec.at(i);
533 *distance = last_value;
565 double dist_cache = (new_start->position()-
Pose(0).
position()).norm();
567 int lookahead = std::min<int>(
sizePoses()-min_samples, 10);
570 for (
int i = 1; i<=lookahead; ++i)
572 dist = (new_start->position()-
Pose(i).
position()).norm();
591 Pose(0) = *new_start;
606 double radius_sq = radius*radius;
607 double max_dist_behind_robot_sq = max_dist_behind_robot*max_dist_behind_robot;
610 for (
int i=1; i<
sizePoses(); i=i+skip_poses+1)
613 double dist_sq = dist_vec.squaredNorm();
615 if (dist_sq > radius_sq)
622 if (max_dist_behind_robot >= 0 && dist_vec.dot(robot_orient) < 0 && dist_sq > max_dist_behind_robot_sq)
void setTimeDiffVertexFixed(int index, bool status)
Set a timediff vertex at pos index of the timediff sequence to be fixed or unfixed during optimizatio...
void deleteTimeDiffs(int index, int number)
Delete multiple (number) time differences starting at pos. index in the timediff sequence.
double getAccumulatedDistance() const
Calculate the length (accumulated euclidean distance) of the trajectory.
void insertPose(int index, const PoseSE2 &pose)
Insert a new pose vertex at pos. index to the pose sequence.
virtual const Eigen::Vector2d & getCentroid() const =0
Get centroid coordinates of the obstacle.
Eigen::Vector2d & position()
Access the 2D position part.
PoseSequence pose_vec_
Internal container storing the sequence of optimzable pose vertices.
double getSumOfAllTimeDiffs() const
Calculate the total transition time (sum over all time intervals of the timediff sequence) ...
static double getYaw(const Quaternion &bt_q)
static PoseSE2 average(const PoseSE2 &pose1, const PoseSE2 &pose2)
Get the mean / average of two poses and return the result (static) For the position part: 0...
bool initTrajectoryToGoal(const PoseSE2 &start, const PoseSE2 &goal, double diststep=0, double max_vel_x=0.5, int min_samples=3, bool guess_backwards_motion=false)
Initialize a trajectory between a given start and goal pose.
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
void addPoseAndTimeDiff(const PoseSE2 &pose, double dt)
Append a (pose, timediff) vertex pair to the end of the current trajectory (pose and timediff sequenc...
double & x()
Access the x-coordinate the pose.
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
PoseSE2 & BackPose()
Access the last PoseSE2 in the pose sequence.
void updateAndPruneTEB(boost::optional< const PoseSE2 & > new_start, boost::optional< const PoseSE2 & > new_goal, int min_samples=3)
Hot-Start from an existing trajectory with updated start and goal poses.
void addPose(const PoseSE2 &pose, bool fixed=false)
Append a new pose vertex to the back of the pose sequence.
Implements a polygon obstacle with an arbitrary number of vertices.
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
Implements a 2D line obstacle.
int findClosestTrajectoryPose(const Eigen::Ref< const Eigen::Vector2d > &ref_point, double *distance=NULL, int begin_idx=0) const
Find the closest point on the trajectory w.r.t. to a provided reference point.
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
void deletePose(int index)
Delete pose at pos. index in the pose sequence.
void deletePoses(int index, int number)
Delete multiple (number) poses starting at pos. index in the pose sequence.
const Eigen::Vector2d & position() const
Return the current position of the obstacle (read-only)
int sizeTimeDiffs() const
Get the length of the internal timediff sequence.
double & TimeDiff(int index)
Access the time difference at pos index of the time sequence.
Implements a 2D point obstacle.
bool isTrajectoryInsideRegion(double radius, double max_dist_behind_robot=-1, int skip_poses=0)
Check if all trajectory points are contained in a specific region.
TimeDiffSequence timediff_vec_
Internal container storing the sequence of optimzable timediff vertices.
double distance_point_to_segment_2d(const Eigen::Ref< const Eigen::Vector2d > &point, const Eigen::Ref< const Eigen::Vector2d > &line_start, const Eigen::Ref< const Eigen::Vector2d > &line_end)
Helper function to calculate the distance between a line segment and a point.
void clearTimedElasticBand()
clear all poses and timediffs from the trajectory. The pose and timediff sequences will be empty and ...
PoseSE2 & Pose(int index)
Access the pose at pos index of the pose sequence.
double & y()
Access the y-coordinate the pose.
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
virtual ~TimedElasticBand()
Destruct the class.
void addTimeDiff(double dt, bool fixed=false)
Append a new time difference vertex to the back of the time diff sequence.
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized...
void deleteTimeDiff(int index)
Delete pose at pos. index in the timediff sequence.
double getSumOfTimeDiffsUpToIdx(int index) const
Calculate the estimated transition time up to the pose denoted by index.
void setPoseVertexFixed(int index, bool status)
Set a pose vertex at pos index of the pose sequence to be fixed or unfixed during optimization...
TimedElasticBand()
Construct the class.
void insertTimeDiff(int index, double dt)
Insert a new timediff vertex at pos. index to the timediff sequence.
void autoResize(double dt_ref, double dt_hysteresis, int min_samples=3, int max_samples=1000, bool fast_mode=false)
Resize the trajectory by removing or inserting a (pose,dt) pair depending on a reference temporal res...
int sizePoses() const
Get the length of the internal pose sequence.
bool isInit() const
Check whether the trajectory is initialized (nonzero pose and timediff sequences) ...
Abstract class that defines the interface for modelling obstacles.
This class stores and wraps a time difference into a vertex that can be optimized via g2o...