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)
241 if (fast_mode)
break;
252 time += (*dt_it)->dt();
263 for(
int i = 0; i < index; ++i)
289 double timestep = 0.1;
294 double dir_to_goal = std::atan2(point_to_goal[1],point_to_goal[0]);
295 double dx = diststep*std::cos(dir_to_goal);
296 double dy = diststep*std::sin(dir_to_goal);
297 double orient_init = dir_to_goal;
300 orient_init = g2o::normalize_theta(orient_init+M_PI);
303 double dist_to_goal = point_to_goal.norm();
304 double no_steps_d = dist_to_goal/std::abs(diststep);
305 unsigned int no_steps = (
unsigned int) std::floor(no_steps_d);
307 if (max_vel_x > 0) timestep = diststep / max_vel_x;
309 for (
unsigned int i=1; i<=no_steps; i++)
311 if (i==no_steps && no_steps_d==(
float) no_steps)
321 ROS_DEBUG(
"initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
338 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)!");
351 PoseSE2 start(plan.front().pose);
352 PoseSE2 goal(plan.back().pose);
359 bool backwards =
false;
360 if (guess_backwards_motion && (goal.position()-start.position()).
dot(start.orientationUnitVec()) < 0)
364 for (
int i=1; i<(int)plan.size()-1; ++i)
370 double dx = plan[i+1].pose.position.x - plan[i].pose.position.x;
371 double dy = plan[i+1].pose.position.y - plan[i].pose.position.y;
372 yaw = std::atan2(dy,dx);
374 yaw = g2o::normalize_theta(yaw+M_PI);
380 PoseSE2 intermediate_pose(plan[i].pose.position.x, plan[i].pose.position.y, yaw);
388 ROS_DEBUG(
"initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
399 if (max_vel_x > 0) dt = (goal.position()-
BackPose().
position()).norm()/max_vel_x;
405 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)!");
416 std::vector<double> dist_vec;
422 for (
int i = begin_idx; i < n; i++)
425 dist_vec.push_back(diff.norm());
428 if (dist_vec.empty())
434 double last_value = dist_vec.at(0);
435 for (
int i=1; i < (int)dist_vec.size(); i++)
437 if (dist_vec.at(i) < last_value)
439 last_value = dist_vec.at(i);
444 *distance = last_value;
445 return begin_idx+index_min;
451 std::vector<double> dist_vec;
457 for (
int i = 0; i < n; i++)
461 dist_vec.push_back(diff);
464 if (dist_vec.empty())
470 double last_value = dist_vec.at(0);
471 for (
int i=1; i < (int)dist_vec.size(); i++)
473 if (dist_vec.at(i) < last_value)
475 last_value = dist_vec.at(i);
480 *distance = last_value;
486 if (vertices.empty())
488 else if (vertices.size() == 1)
490 else if (vertices.size() == 2)
493 std::vector<double> dist_vec;
499 for (
int i = 0; i < n; i++)
502 double diff = HUGE_VAL;
503 for (
int j = 0; j < (int) vertices.size()-1; ++j)
508 dist_vec.push_back(diff);
511 if (dist_vec.empty())
517 double last_value = dist_vec.at(0);
518 for (
int i=1; i < (int)dist_vec.size(); i++)
520 if (dist_vec.at(i) < last_value)
522 last_value = dist_vec.at(i);
527 *distance = last_value;
557 d_start_goal.normalize();
562 Eigen::Vector2d orient_vector(
cos(
Pose(i).theta() ),
sin(
Pose(i).theta() ) );
563 if (orient_vector.dot(d_start_goal) < threshold)
565 ROS_DEBUG(
"detectDetoursBackwards() - mark TEB for deletion: start-orientation vs startgoal-vec");
599 double dist_cache = (new_start->position()-
Pose(0).
position()).norm();
601 int lookahead = std::min<int>(
sizePoses()-min_samples, 10);
604 for (
int i = 1; i<=lookahead; ++i)
606 dist = (new_start->position()-
Pose(i).
position()).norm();
625 Pose(0) = *new_start;
640 double radius_sq = radius*radius;
641 double max_dist_behind_robot_sq = max_dist_behind_robot*max_dist_behind_robot;
644 for (
int i=1; i<
sizePoses(); i=i+skip_poses+1)
647 double dist_sq = dist_vec.squaredNorm();
649 if (dist_sq > radius_sq)
656 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.
bool detectDetoursBackwards(double threshold=0) const
Detect whether the trajectory contains detours.
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.
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
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) ...
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
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...