46 template<
typename B
idirIter,
typename Fun>
48 boost::optional<double> max_acc_x, boost::optional<double> max_acc_theta,
49 boost::optional<double> start_orientation, boost::optional<double> goal_orientation,
int min_samples,
bool guess_backwards_motion)
52 Eigen::Vector2d
goal_position = fun_position( *boost::prior(path_end) );
54 bool backwards =
false;
56 double start_orient, goal_orient;
57 if (start_orientation)
59 start_orient = *start_orientation;
62 if (guess_backwards_motion && (goal_position-start_position).
dot(Eigen::Vector2d(std::cos(start_orient), std::sin(start_orient))) < 0)
68 start_orient =
atan2(start2goal[1],start2goal[0]);
75 goal_orient = *goal_orientation;
79 goal_orient = start_orient;
84 addPose(start_position, start_orient,
true);
87 std::advance(path_start,1);
88 std::advance(path_end,-1);
90 for (; path_start != path_end; ++path_start)
95 Eigen::Vector2d curr_point = fun_position(*path_start);
96 Eigen::Vector2d diff_last = curr_point -
Pose(idx).
position();
98 double diff_norm = diff_last.norm();
100 double timestep_vel = diff_norm/max_vel_x;
105 timestep_acc =
sqrt(2*diff_norm/(*max_acc_x));
106 if (timestep_vel < timestep_acc && max_acc_x) timestep = timestep_acc;
107 else timestep = timestep_vel;
109 else timestep = timestep_vel;
111 if (timestep<0) timestep=0.2;
113 double yaw =
atan2(diff_last[1],diff_last[0]);
115 yaw = g2o::normalize_theta(yaw + M_PI);
146 double diff_norm = diff.norm();
147 double timestep_vel = diff_norm/max_vel_x;
150 double timestep_acc =
sqrt(2*diff_norm/(*max_acc_x));
151 if (timestep_vel < timestep_acc) timestep = timestep_acc;
152 else timestep = timestep_vel;
154 else timestep = timestep_vel;
157 PoseSE2 goal(goal_position, goal_orient);
162 ROS_DEBUG(
"initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples...");
178 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)!");
Eigen::Vector2d & position()
Access the 2D position part.
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...
PoseSE2 & BackPose()
Access the last PoseSE2 in the pose sequence.
void addPose(const PoseSE2 &pose, bool fixed=false)
Append a new pose vertex to the back of the pose sequence.
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
int sizeTimeDiffs() const
Get the length of the internal timediff sequence.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
PoseSE2 & Pose(int index)
Access the pose at pos index of the pose sequence.
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
void setPoseVertexFixed(int index, bool status)
Set a pose vertex at pos index of the pose sequence to be fixed or unfixed during optimization...
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) ...