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;
68 start_orient = atan2(start2goal[1],start2goal[0]);
75 goal_orient = *goal_orientation;
79 goal_orient = start_orient;
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;
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)!");