92       ROS_WARN(
"This planner has already been initialized, doing nothing.");
    97     eband_local_planner::EBandPlannerConfig& config)
   133       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
   139     if(global_plan.size() < 2)
   141       ROS_ERROR(
"Attempt to pass empty path to optimization. Valid path needs to have at least 2 Frames. This one has %d.", ((
int) global_plan.size()) );
   151       ROS_ERROR(
"Elastic Band expects plan for optimization in the %s frame, the plan was sent in the %s frame.",
   161       ROS_WARN(
"Conversion from plan to elastic band failed. Plan probably not collision free. Plan not set for optimization");
   171       ROS_WARN(
"Band is broken. Could not close gaps in converted path. Path not set. Global replanning needed");
   176     ROS_DEBUG(
"Refinement done - Band set.");
   186       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
   193       ROS_WARN(
"Band is empty. There was no path successfully set so far.");
   200       ROS_WARN(
"Conversion from Elastic Band to path failed.");
   213       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
   235       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
   242       ROS_WARN(
"Attempt to connect path to empty band. path not connected. Use SetPath instead");
   247     if(plan_to_add.empty())
   249       ROS_WARN(
"Attempt to connect empty path to band. Nothing to do here.");
   256       ROS_ERROR(
"Elastic Band expects robot pose for optimization in the %s frame, the pose was sent in the %s frame.",
   263     std::vector<Bubble> band_to_add;
   266       ROS_DEBUG(
"Conversion from plan to elastic band failed. Plan not appended");
   273     ROS_DEBUG(
"Checking for connections between current band and new bubbles");
   274     bool connected = 
false;
   275     int bubble_connect = -1;
   308     std::vector<Bubble> tmp_band;
   309     std::vector<Bubble>::iterator tmp_iter1, tmp_iter2;
   311     tmp_band.assign(band_to_add.begin(), band_to_add.end());
   315       ROS_DEBUG(
"Connections found - composing new band by connecting new frames to bubble %d", bubble_connect);
   321         tmp_band.insert(tmp_band.end(), tmp_iter1, 
elastic_band_.end());
   328         tmp_band.insert(tmp_band.begin(), 
elastic_band_.begin(), tmp_iter1);
   337     ROS_DEBUG(
"No direct connection found - Composing tmp band and trying to fill gap");
   343       tmp_iter1 = tmp_band.begin() + ((int) band_to_add.size()) - 1;
   344       tmp_iter2 = tmp_iter1 + 1;
   351       tmp_iter1 = tmp_band.begin() + ((int) 
elastic_band_.size()) - 1;
   352       tmp_iter2 = tmp_iter1 + 1;
   359     if(!
fillGap(tmp_band, tmp_iter1, tmp_iter2))
   362       ROS_DEBUG(
"Could not connect robot pose to band - Failed to fill gap.");
   378       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
   385       ROS_ERROR(
"Band is empty. Probably Band has not been set yet");
   390     ROS_DEBUG(
"Starting optimization of band");
   393       ROS_DEBUG(
"Aborting Optimization. Changes discarded.");
   397     ROS_DEBUG(
"Elastic Band - Optimization successfull!");
   407       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
   414       ROS_ERROR(
"Elastic Band expects plan for optimization in the %s frame, the plan was sent in the %s frame.",
   420     for(
int i = 0; i < ((int) band.size()); i++)
   425         ROS_DEBUG(
"Optimization (Elastic Band) - Calculation of Distance failed. Frame %d of %d Probably outside map coordinates.",
   426             i, ((
int) band.size()) );
   433         ROS_DEBUG(
"Optimization (Elastic Band) - Calculation of Distance failed. Frame %d of %d in collision. Plan invalid. Trying to refine band.",
   434             i, ((
int) band.size()) );
   439       band.at(i).expansion = distance;
   445       ROS_DEBUG(
"Elastic Band is broken. Could not close gaps in band. Global replanning needed.");
   450     std::vector<Bubble> tmp_band = band;
   455       ROS_DEBUG(
"Inside optimization: Cycle no %d", i);
   460         ROS_DEBUG(
"Optimization failed while trying to modify Band.");
   468         ROS_DEBUG(
"Optimization failed while trying to refine modified band");
   487       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
   494       ROS_WARN(
"Attempt to convert empty band to plan. Valid band needs to have at least 2 Frames. This one has %d.", ((
int) band.size()) );
   500     std::vector<Bubble> tmp_band;
   501     std::vector<Bubble>::iterator start_iter, end_iter;
   505     start_iter = tmp_band.begin();
   506     end_iter = (tmp_band.end() - 1); 
   511       ROS_DEBUG(
"Band is broken. Could not close gaps.");
   515       ROS_DEBUG(
"Recursive filling and removing DONE");
   528     std::vector<Bubble>::iterator tmp_iter;
   529     int mid_int, diff_int;
   532     int debug_dist_start, debug_dist_iters;
   533     debug_dist_start = std::distance(band.begin(), start_iter);
   534     debug_dist_iters = std::distance(start_iter, end_iter);
   535     ROS_DEBUG(
"Refining Recursive - Check if Bubbles %d and %d overlapp. Total size of band %d.", debug_dist_start, (debug_dist_start + debug_dist_iters), ((
int) band.size()) );
   550       ROS_DEBUG(
"Refining Recursive - Bubbles overlapp, check for redundancies");
   554       if((start_iter + 1) < end_iter)
   557         ROS_DEBUG(
"Refining Recursive - Bubbles overlapp, removing Bubbles %d to %d.", (debug_dist_start + 1), (debug_dist_start + debug_dist_iters -1));
   561         tmp_iter = band.erase((start_iter+1), end_iter);
   568       ROS_DEBUG(
"Refining Recursive - Bubbles overlapp - DONE");
   577     if((start_iter + 1) < end_iter)
   580       ROS_DEBUG(
"Refining Recursive - Bubbles do not overlapp, go one recursion deeper");
   585       mid_int = std::distance(start_iter, end_iter);
   589       tmp_iter = start_iter + mid_int;
   591       diff_int = (int) std::distance(tmp_iter, end_iter);
   594       ROS_ASSERT( start_iter >= band.begin() );
   595       ROS_ASSERT( end_iter < band.end() ); 
   596       ROS_ASSERT( start_iter < end_iter );
   608       end_iter = tmp_iter + diff_int;
   611       ROS_ASSERT( start_iter >= band.begin() );
   612       ROS_ASSERT( end_iter < band.end() ); 
   613       ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
   618       diff_int = (int) std::distance(start_iter, tmp_iter);
   626       start_iter = tmp_iter - diff_int;
   629       ROS_ASSERT( start_iter >= band.begin() );
   630       ROS_ASSERT( end_iter < band.end() ); 
   631       ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
   641         ROS_DEBUG(
"Refining Recursive - Removing middle bubble");
   645         diff_int = (int) std::distance((tmp_iter + 1), end_iter);
   648         tmp_iter = band.erase(tmp_iter);
   649         end_iter = tmp_iter + diff_int;
   653       ROS_ASSERT( start_iter >= band.begin() );
   654       ROS_ASSERT( end_iter < band.end() ); 
   655       ROS_ASSERT( start_iter < end_iter );
   658       ROS_DEBUG(
"Refining Recursive - Bubbles do not overlapp, go one recursion deeper DONE");
   667     ROS_DEBUG(
"Refining Recursive - Gap detected, fill recursive");
   671     if(!
fillGap(band, start_iter, end_iter))
   674       ROS_DEBUG(
"Failed to fill gap between bubble %d and %d.", (
int) 
distance(band.begin(), start_iter), (
int) 
distance(band.begin(), end_iter) );
   679     ROS_DEBUG(
"Refining Recursive - Gap detected, fill recursive DONE");
   687   bool EBandPlanner::fillGap(std::vector<Bubble>& band, std::vector<Bubble>::iterator& start_iter,std::vector<Bubble>::iterator& end_iter)
   694     Bubble interpolated_bubble;
   695     geometry_msgs::PoseStamped interpolated_center;
   696     std::vector<Bubble>::iterator tmp_iter;
   697     int diff_int, start_num, end_num;
   706     ROS_DEBUG(
"Fill recursive - interpolate");
   713       start_num = std::distance(band.begin(), start_iter);
   714       end_num = std::distance(band.begin(), end_iter);
   715       ROS_DEBUG(
"Interpolation failed while trying to fill gap between bubble %d and %d.", start_num, end_num);
   721     ROS_DEBUG(
"Fill recursive - calc expansion of interpolated bubble");
   728       start_num = std::distance(band.begin(), start_iter);
   729       end_num = std::distance(band.begin(), end_iter);
   730       ROS_DEBUG(
"Calculation of Distance failed for interpolated bubble - failed to fill gap between bubble %d and %d.", start_num, end_num);
   737       start_num = std::distance(band.begin(), start_iter);
   738       end_num = std::distance(band.begin(), end_iter);
   739       ROS_DEBUG(
"Interpolated Bubble in Collision - failed to fill gap between bubble %d and %d.", start_num, end_num);
   746     ROS_DEBUG(
"Fill recursive - inserting interpolated bubble at (%f, %f), with expansion %f", interpolated_center.pose.position.x, interpolated_center.pose.position.y, distance);
   750     interpolated_bubble.
center = interpolated_center;
   751     interpolated_bubble.
expansion = distance;
   753     tmp_iter = band.insert(end_iter, interpolated_bubble);
   755     start_iter = tmp_iter - 1;
   756     end_iter = tmp_iter + 1;
   759     ROS_ASSERT( start_iter >= band.begin() );
   760     ROS_ASSERT( end_iter < band.end() ); 
   761     ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
   765     ROS_DEBUG(
"Fill recursive - check overlap interpolated bubble and first bubble");
   773       ROS_DEBUG(
"Fill recursive - gap btw. interpolated and first bubble - fill recursive");
   777       if(!
fillGap(band, start_iter, tmp_iter))
   783       end_iter = tmp_iter + 1;
   787     ROS_ASSERT( start_iter >= band.begin() );
   788     ROS_ASSERT( end_iter < band.end() ); 
   789     ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
   793     ROS_DEBUG(
"Fill recursive - check overlap interpolated bubble and second bubble");
   800       ROS_DEBUG(
"Fill recursive - gap btw. interpolated and second bubble - fill recursive");
   804       diff_int = (int) std::distance(start_iter, tmp_iter);
   807       if(!
fillGap(band, tmp_iter, end_iter))
   813       start_iter = tmp_iter - diff_int;
   817     ROS_ASSERT( start_iter >= band.begin() );
   818     ROS_ASSERT( end_iter < band.end() ); 
   819     ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
   823     ROS_DEBUG(
"Fill recursive - gap closed");
   837       ROS_ERROR(
"Trying to modify an empty band.");
   847     std::vector<geometry_msgs::WrenchStamped> internal_forces, external_forces, forces;
   848     geometry_msgs::WrenchStamped wrench;
   858     wrench.header.frame_id = band[0].center.header.frame_id;
   859     wrench.wrench.force.x = 0.0;
   860     wrench.wrench.force.y = 0.0;
   861     wrench.wrench.force.z = 0.0;
   862     wrench.wrench.torque.x = 0.0;
   863     wrench.wrench.torque.y = 0.0;
   864     wrench.wrench.torque.z = 0.0;
   865     internal_forces.assign(band.size(), wrench);
   866     external_forces = internal_forces;
   867     forces = internal_forces;
   878     while( (i>0) && (i < ((int) band.size() - 1)) )
   884       ROS_DEBUG(
"Calculating internal force for bubble %d.", i);
   890         ROS_DEBUG(
"Calculation of internal forces failed");
   899       ROS_DEBUG(
"Calculating external force for bubble %d.", i);
   907         ROS_DEBUG(
"Calculation of external forces failed");
   916       ROS_DEBUG(
"Superposing internal and external forces");
   921       forces.at(i).wrench.force.x = internal_forces.at(i).wrench.force.x + external_forces.at(i).wrench.force.x;
   922       forces.at(i).wrench.force.y = internal_forces.at(i).wrench.force.y + external_forces.at(i).wrench.force.y;
   923       forces.at(i).wrench.force.z = internal_forces.at(i).wrench.force.z + external_forces.at(i).wrench.force.z;
   925       forces.at(i).wrench.torque.x = internal_forces.at(i).wrench.torque.x + external_forces.at(i).wrench.torque.x;
   926       forces.at(i).wrench.torque.y = internal_forces.at(i).wrench.torque.y + external_forces.at(i).wrench.torque.y;
   927       forces.at(i).wrench.torque.z = internal_forces.at(i).wrench.torque.z + external_forces.at(i).wrench.torque.z;
   930       ROS_DEBUG(
"Superpose forces: (x, y, theta) = (%f, %f, %f)", forces.at(i).wrench.force.x, forces.at(i).wrench.force.y, forces.at(i).wrench.torque.z);
   931       ROS_DEBUG(
"Supressing tangential forces");
   937         ROS_DEBUG(
"Supression of tangential forces failed");
   948       ROS_DEBUG(
"Applying forces to modify band");
   952         ROS_DEBUG(
"Band is invalid - Stopping Modification");
   970         if(i == ((
int) band.size() - 1))
   975           ROS_DEBUG(
"Optimization Elastic Band - Forward cycle done, starting backward cycle");
   997     geometry_msgs::Pose2D bubble_pose2D, new_bubble_pose2D;
   998     geometry_msgs::Pose bubble_pose, new_bubble_pose;
   999     geometry_msgs::Twist bubble_jump;
  1000     Bubble new_bubble = band.at(bubble_num);
  1005     bubble_pose = band.at(bubble_num).center.pose;
  1009     bubble_jump.linear.x = band.at(bubble_num).expansion*forces.at(bubble_num).wrench.force.x;
  1010     bubble_jump.linear.y = band.at(bubble_num).expansion*forces.at(bubble_num).wrench.force.y;
  1011     bubble_jump.linear.z = 0.0;
  1012     bubble_jump.angular.x = 0.0;
  1013     bubble_jump.angular.y = 0.0;
  1018     new_bubble_pose2D.x = bubble_pose2D.x + bubble_jump.linear.x;
  1019     new_bubble_pose2D.y = bubble_pose2D.y + bubble_jump.linear.y;
  1020     new_bubble_pose2D.theta = bubble_pose2D.theta + bubble_jump.angular.z;
  1025     new_bubble.
center.pose = new_bubble_pose;
  1028     ROS_DEBUG(
"Try moving bubble %d at (%f, %f, %f) by (%f, %f, %f).", bubble_num, bubble_pose2D.x, bubble_pose2D.y, bubble_pose2D.theta,
  1029         bubble_jump.linear.x, bubble_jump.linear.y, bubble_jump.angular.z);
  1038       ROS_DEBUG(
"Calculation of Distance failed. Frame %d of %d Probably outside map. Discarding Changes", bubble_num, ((
int) band.size()) );
  1052       ROS_DEBUG(
"Calculation of Distance failed. Frame %d of %d in collision. Plan invalid. Discarding Changes", bubble_num, ((
int) band.size()) );
  1069     geometry_msgs::WrenchStamped new_bubble_force = forces.at(bubble_num);
  1072     if(!
getForcesAt(bubble_num, band, new_bubble, new_bubble_force))
  1075       ROS_DEBUG(
"Cannot calculate forces on bubble %d at new position - discarding changes", bubble_num);
  1080     ROS_DEBUG(
"Check for zero-crossings in force on bubble %d", bubble_num);
  1084     double checksum_zero, abs_new_force, abs_old_force;
  1087     checksum_zero = (new_bubble_force.wrench.force.x * forces.at(bubble_num).wrench.force.x) +
  1088       (new_bubble_force.wrench.force.y * forces.at(bubble_num).wrench.force.y) +
  1089       (new_bubble_force.wrench.torque.z * forces.at(bubble_num).wrench.torque.z);
  1092     if(checksum_zero < 0.0)
  1094       ROS_DEBUG(
"Detected zero-crossings in force on bubble %d. Checking total change in force.", bubble_num);
  1096       abs_new_force = 
sqrt( (new_bubble_force.wrench.force.x * new_bubble_force.wrench.force.x) +
  1097           (new_bubble_force.wrench.force.y * new_bubble_force.wrench.force.y) +
  1098           (new_bubble_force.wrench.torque.z * new_bubble_force.wrench.torque.z) );
  1099       abs_old_force = 
sqrt( (forces.at(bubble_num).wrench.force.x * forces.at(bubble_num).wrench.force.x) +
  1100           (forces.at(bubble_num).wrench.force.x * forces.at(bubble_num).wrench.force.x) +
  1101           (forces.at(bubble_num).wrench.torque.z * forces.at(bubble_num).wrench.torque.z) );
  1106         ROS_DEBUG(
"Detected significante change in force (%f to %f) on bubble %d. Entering Recursive Approximation.", abs_old_force, abs_new_force, bubble_num);
  1108         int curr_recursion_depth = 0;
  1109         geometry_msgs::Twist new_step_width;
  1110         Bubble curr_bubble = band.at(bubble_num);
  1111         geometry_msgs::WrenchStamped curr_bubble_force = forces.at(bubble_num);
  1114         new_step_width.linear.x = 0.5*bubble_jump.linear.x;
  1115         new_step_width.linear.y = 0.5*bubble_jump.linear.y;
  1116         new_step_width.linear.z = 0.5*bubble_jump.linear.z;
  1117         new_step_width.angular.x = 0.5*bubble_jump.angular.x;
  1118         new_step_width.angular.y = 0.5*bubble_jump.angular.y;
  1119         new_step_width.angular.z = 0.5*bubble_jump.angular.z;
  1125           new_bubble = curr_bubble;
  1128           geometry_msgs::Pose2D curr_bubble_pose2D;
  1130           ROS_DEBUG(
"Instead - Try moving bubble %d at (%f, %f, %f) by (%f, %f, %f) to (%f, %f, %f).",
  1131               bubble_num, bubble_pose2D.x, bubble_pose2D.y, bubble_pose2D.theta,
  1132               new_step_width.linear.x, new_step_width.linear.y, new_step_width.angular.z,
  1133               curr_bubble_pose2D.x, curr_bubble_pose2D.y, curr_bubble_pose2D.theta);
  1144     std::vector<Bubble> tmp_band = band;
  1145     std::vector<Bubble>::iterator start_iter, end_iter;
  1146     tmp_band.at(bubble_num) = new_bubble;
  1147     start_iter = tmp_band.begin();
  1150     start_iter = start_iter + bubble_num - 1;
  1151     end_iter = start_iter + 1;
  1156       if(!
fillGap(tmp_band, start_iter, end_iter))
  1158         ROS_DEBUG(
"Bubble at new position cannot be connected to neighbour. Discarding changes.");
  1167     tmp_band.at(bubble_num) = new_bubble;
  1168     start_iter = tmp_band.begin();
  1171     start_iter = start_iter + bubble_num;
  1172     end_iter = start_iter + 1;
  1177       if(!
fillGap(tmp_band, start_iter, end_iter))
  1179         ROS_DEBUG(
"Bubble at new position cannot be connected to neighbour. Discarding changes.");
  1189     ROS_DEBUG(
"Frame %d of %d: Check successful - bubble and band valid. Applying Changes", bubble_num, ((
int) band.size()) );
  1192     band.at(bubble_num) = new_bubble;
  1199       const geometry_msgs::WrenchStamped& curr_bubble_force, geometry_msgs::Twist& curr_step_width, 
const int& curr_recursion_depth)
  1203     Bubble new_bubble = curr_bubble;
  1204     geometry_msgs::Pose2D new_bubble_pose2D, curr_bubble_pose2D;
  1205     geometry_msgs::WrenchStamped new_bubble_force = curr_bubble_force;
  1212     new_bubble_pose2D.x = curr_bubble_pose2D.x + curr_step_width.linear.x;
  1213     new_bubble_pose2D.y = curr_bubble_pose2D.y + curr_step_width.linear.y;
  1214     new_bubble_pose2D.theta = curr_bubble_pose2D.theta + curr_step_width.angular.z;
  1236     if(!
getForcesAt(bubble_num, band, new_bubble, new_bubble_force))
  1240     curr_bubble = new_bubble;
  1251     ROS_DEBUG(
"Check for zero-crossings in force on bubble %d - Recursion %d", bubble_num, curr_recursion_depth);
  1254     double checksum_zero, abs_new_force, abs_old_force;
  1255     int new_recursion_depth;
  1256     geometry_msgs::Twist new_step_width;
  1259     checksum_zero = (new_bubble_force.wrench.force.x * curr_bubble_force.wrench.force.x) +
  1260       (new_bubble_force.wrench.force.y * curr_bubble_force.wrench.force.y) +
  1261       (new_bubble_force.wrench.torque.z * curr_bubble_force.wrench.torque.z);
  1263     if(checksum_zero < 0.0)
  1266       ROS_DEBUG(
"Detected zero-crossings in force on bubble %d - Recursion %d. Checking total change in force.", bubble_num, curr_recursion_depth);
  1270       abs_new_force = 
sqrt( (new_bubble_force.wrench.force.x * new_bubble_force.wrench.force.x) +
  1271           (new_bubble_force.wrench.force.y * new_bubble_force.wrench.force.y) +
  1272           (new_bubble_force.wrench.torque.z * new_bubble_force.wrench.torque.z) );
  1273       abs_old_force = 
sqrt( (curr_bubble_force.wrench.force.x * curr_bubble_force.wrench.force.x) +
  1274           (curr_bubble_force.wrench.force.x * curr_bubble_force.wrench.force.x) +
  1275           (curr_bubble_force.wrench.torque.z * curr_bubble_force.wrench.torque.z) );
  1280         ROS_DEBUG(
"Detected significant change in force (%f to %f) on bubble %d - Recursion %d. Going one Recursion deeper.", abs_old_force, abs_new_force, bubble_num, curr_recursion_depth);
  1284         new_recursion_depth = curr_recursion_depth + 1;
  1286         new_step_width.linear.x = -0.5*curr_step_width.linear.x;
  1287         new_step_width.linear.y = -0.5*curr_step_width.linear.y;
  1288         new_step_width.linear.z = -0.5*curr_step_width.linear.z;
  1289         new_step_width.angular.x = -0.5*curr_step_width.angular.x;
  1290         new_step_width.angular.y = -0.5*curr_step_width.angular.y;
  1291         new_step_width.angular.z = -0.5*curr_step_width.angular.z;
  1296           curr_bubble = new_bubble;
  1306       ROS_DEBUG(
"No zero-crossings in force on bubble %d - Recursion %d. Continue walk in same direction. Going one recursion deeper.", bubble_num, curr_recursion_depth);
  1310       new_recursion_depth = curr_recursion_depth + 1;
  1312       new_step_width.linear.x = 0.5*curr_step_width.linear.x;
  1313       new_step_width.linear.y = 0.5*curr_step_width.linear.y;
  1314       new_step_width.linear.z = 0.5*curr_step_width.linear.z;
  1315       new_step_width.angular.x = 0.5*curr_step_width.angular.x;
  1316       new_step_width.angular.y = 0.5*curr_step_width.angular.y;
  1317       new_step_width.angular.z = 0.5*curr_step_width.angular.z;
  1322         curr_bubble = new_bubble;
  1334     geometry_msgs::WrenchStamped internal_force, external_force;
  1339       ROS_DEBUG(
"Calculation of internal forces failed");
  1346       ROS_DEBUG(
"Calculation of external forces failed");
  1351     forces.wrench.force.x = internal_force.wrench.force.x + external_force.wrench.force.x;
  1352     forces.wrench.force.y = internal_force.wrench.force.y + external_force.wrench.force.y;
  1353     forces.wrench.force.z = internal_force.wrench.force.z + external_force.wrench.force.z;
  1355     forces.wrench.torque.x = internal_force.wrench.torque.x + external_force.wrench.torque.x;
  1356     forces.wrench.torque.y = internal_force.wrench.torque.y + external_force.wrench.torque.y;
  1357     forces.wrench.torque.z = internal_force.wrench.torque.z + external_force.wrench.torque.z;
  1362       ROS_DEBUG(
"Supression of tangential forces failed");
  1375       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
  1380     if(band.size() <= 2)
  1388     geometry_msgs::Twist difference1, difference2;
  1389     geometry_msgs::Wrench wrench;
  1393     ROS_ASSERT( bubble_num < ((
int) band.size() - 1) );
  1399       ROS_ERROR(
"Failed to calculate Distance between two bubbles. Aborting calculation of internal forces!");
  1405       ROS_ERROR(
"Failed to calculate Distance between two bubbles. Aborting calculation of internal forces!");
  1412       ROS_ERROR(
"Failed to calculate Difference between two bubbles. Aborting calculation of internal forces!");
  1418       ROS_ERROR(
"Failed to calculate Difference between two bubbles. Aborting calculation of internal forces!");
  1425       distance1 = 1000000.0;
  1427       distance2 = 1000000.0;
  1430     wrench.force.x = 
internal_force_gain_*(difference1.linear.x/distance1 + difference2.linear.x/distance2);
  1431     wrench.force.y = 
internal_force_gain_*(difference1.linear.y/distance1 + difference2.linear.y/distance2);
  1432     wrench.force.z = 
internal_force_gain_*(difference1.linear.z/distance1 + difference2.linear.z/distance2);
  1433     wrench.torque.x = 
internal_force_gain_*(difference1.angular.x/distance1 + difference2.angular.x/distance2);
  1434     wrench.torque.y = 
internal_force_gain_*(difference1.angular.y/distance1 + difference2.angular.y/distance2);
  1435     wrench.torque.z = 
internal_force_gain_*(difference1.angular.z/distance1 + difference2.angular.z/distance2);
  1438     ROS_DEBUG(
"Calculating internal forces: (x, y, theta) = (%f, %f, %f)", wrench.force.x, wrench.force.y, wrench.torque.z);
  1442     forces.wrench = wrench;
  1453       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
  1459     geometry_msgs::Pose edge;
  1460     geometry_msgs::Pose2D edge_pose2D;
  1461     geometry_msgs::Wrench wrench;
  1465     edge = curr_bubble.
center.pose;
  1466     edge.position.x = edge.position.x + curr_bubble.
expansion;
  1470       ROS_DEBUG(
"Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
  1475     edge.position.x = edge.position.x - 2.0*curr_bubble.
expansion;
  1479       ROS_DEBUG(
"Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
  1490       ROS_DEBUG(
"Calculating external forces on broken band. Bubble should have been removed. Local Planner probably ill configured");
  1498     edge = curr_bubble.
center.pose;
  1499     edge.position.y = edge.position.y + curr_bubble.
expansion;
  1503       ROS_DEBUG(
"Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
  1508     edge.position.y = edge.position.y - 2.0*curr_bubble.
expansion;
  1512       ROS_DEBUG(
"Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
  1523       ROS_DEBUG(
"Calculating external forces on broken band. Bubble should have been removed. Local Planner probably ill configured");
  1531     wrench.force.z = 0.0;
  1535     wrench.torque.x = 0.0;
  1536     wrench.torque.y = 0.0;
  1547       ROS_DEBUG(
"Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
  1558       ROS_DEBUG(
"Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
  1569       ROS_DEBUG(
"Calculating external forces on broken band. Bubble should have been removed. Local Planner probably ill configured");
  1577     ROS_DEBUG(
"Calculating external forces: (x, y, theta) = (%f, %f, %f)", wrench.force.x, wrench.force.y, wrench.torque.z);
  1581     forces.wrench = wrench;
  1590     if(band.size() <= 2)
  1596     double scalar_fd, scalar_dd;
  1597     geometry_msgs::Twist difference;
  1601     ROS_ASSERT( bubble_num < ((
int) band.size() - 1) );
  1605     if(!
calcBubbleDifference(band[bubble_num+1].center.pose, band[bubble_num-1].center.pose, difference))
  1610     scalar_fd = forces.wrench.force.x*difference.linear.x + forces.wrench.force.y*difference.linear.y +
  1611       forces.wrench.force.z*difference.linear.z + forces.wrench.torque.x*difference.angular.x +
  1612       forces.wrench.torque.y*difference.angular.y + forces.wrench.torque.z*difference.angular.z;
  1615     scalar_dd = difference.linear.x*difference.linear.x + difference.linear.y*difference.linear.y + difference.linear.z*difference.linear.z +
  1616       difference.angular.x*difference.angular.x + difference.angular.y*difference.angular.y + difference.angular.z*difference.angular.z;
  1622       ROS_DEBUG(
"Calculating tangential forces for redundant bubbles. Bubble should have been removed. Local Planner probably ill configured");
  1626     forces.wrench.force.x = forces.wrench.force.x - scalar_fd/scalar_dd * difference.linear.x;
  1627     forces.wrench.force.y = forces.wrench.force.y - scalar_fd/scalar_dd * difference.linear.y;
  1628     forces.wrench.force.z = forces.wrench.force.z - scalar_fd/scalar_dd * difference.linear.z;
  1629     forces.wrench.torque.x = forces.wrench.torque.x - scalar_fd/scalar_dd * difference.angular.x;
  1630     forces.wrench.torque.y = forces.wrench.torque.y - scalar_fd/scalar_dd * difference.angular.y;
  1631     forces.wrench.torque.z = forces.wrench.torque.z - scalar_fd/scalar_dd * difference.angular.z;
  1634     ROS_DEBUG(
"Supressing tangential forces: (x, y, theta) = (%f, %f, %f)",
  1635         forces.wrench.force.x, forces.wrench.force.y, forces.wrench.torque.z);
  1649       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
  1654     geometry_msgs::Pose2D start_pose2D, end_pose2D, interpolated_pose2D;
  1658     interpolated_center.header = start_center.header;
  1668     delta_theta = end_pose2D.theta - start_pose2D.theta;
  1670     interpolated_pose2D.theta = start_pose2D.theta + delta_theta;
  1673     interpolated_pose2D.x = 0.0;
  1674     interpolated_pose2D.y = 0.0;
  1675     Pose2DToPose(interpolated_center.pose, interpolated_pose2D);
  1678     interpolated_center.pose.position.x = (end_center.pose.position.x + start_center.pose.position.x)/2.0;
  1679     interpolated_center.pose.position.y = (end_center.pose.position.y + start_center.pose.position.y)/2.0;
  1680     interpolated_center.pose.position.z = (end_center.pose.position.z + start_center.pose.position.z)/2.0;
  1693       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
  1701       ROS_ERROR(
"failed to calculate Distance between two bubbles. Aborting check for overlap!");
  1721       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
  1725     geometry_msgs::Pose2D start_pose2D, end_pose2D, diff_pose2D;
  1734     diff_pose2D.theta = end_pose2D.theta - start_pose2D.theta;
  1737     diff_pose2D.x = end_pose2D.x - start_pose2D.x;
  1738     diff_pose2D.y = end_pose2D.y - start_pose2D.y;
  1743     distance = 
sqrt( (diff_pose2D.x * diff_pose2D.x) + (diff_pose2D.y * diff_pose2D.y));
  1756       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
  1760     geometry_msgs::Pose2D start_pose2D, end_pose2D, diff_pose2D;
  1769     diff_pose2D.theta = end_pose2D.theta - start_pose2D.theta;
  1772     diff_pose2D.x = end_pose2D.x - start_pose2D.x;
  1773     diff_pose2D.y = end_pose2D.y - start_pose2D.y;
  1775     difference.linear.x = diff_pose2D.x;
  1776     difference.linear.y = diff_pose2D.y;
  1777     difference.linear.z = 0.0;
  1779     difference.angular.x = 0.0;
  1780     difference.angular.y = 0.0;
  1796       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
  1800     unsigned int cell_x, cell_y;
  1801     unsigned char disc_cost;
  1807     if(!
costmap_->
worldToMap(center_pose.position.x, center_pose.position.y, cell_x, cell_y)) {
  1836       if (disc_cost == 0) { 
  1838       } 
else if (disc_cost == 255) { 
  1842       distance = -
log(factor) / weight;
  1856       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
  1862     std::vector<Bubble> tmp_band;
  1864     ROS_DEBUG(
"Copying plan to band - Conversion started: %d frames to convert.", ((
int) plan.size()) );
  1870     tmp_band.resize(plan.size());
  1871     for(
int i = 0; i < ((int) plan.size()); i++)
  1874       ROS_DEBUG(
"Checking Frame %d of %d", i, ((
int) plan.size()) );
  1878       tmp_band[i].center = plan[i];
  1884         ROS_WARN(
"Calculation of Distance between bubble and nearest obstacle failed. Frame %d of %d outside map", i, ((
int) plan.size()) );
  1891         ROS_WARN(
"Calculation of Distance between bubble and nearest obstacle failed. Frame %d of %d in collision. Plan invalid", i, ((
int) plan.size()) );
  1898       tmp_band[i].expansion = distance;
  1904     ROS_DEBUG(
"Successfully converted plan to band");
  1914       ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
  1919     std::vector<geometry_msgs::PoseStamped> tmp_plan;
  1922     tmp_plan.resize(band.size());
  1923     for(
int i = 0; i < ((int) band.size()); i++)
  1926       tmp_plan[i] = band[i].center;
 
std::vector< geometry_msgs::PoseStamped > global_plan_
costmap_2d::Costmap2D * costmap_
double internal_force_gain_
gain for internal forces ("Elasticity of Band") 
std::vector< Bubble > elastic_band_
bool convertBandToPlan(std::vector< geometry_msgs::PoseStamped > &plan, std::vector< Bubble > band)
This converts a band from a sequence of bubbles into a plan from, a sequence of stamped poses...
bool interpolateBubbles(geometry_msgs::PoseStamped start_center, geometry_msgs::PoseStamped end_center, geometry_msgs::PoseStamped &interpolated_center)
interpolates between two bubbles by calculating the pose for the center of a bubble in the middle of ...
double equilibrium_relative_overshoot_
maximum depth for recursive approximation to constrain computational burden 
bool getPlan(std::vector< geometry_msgs::PoseStamped > &global_plan)
This transforms the refined band to a path again and outputs it. 
INLINE Rall1d< T, V, S > log(const Rall1d< T, V, S > &arg)
double external_force_gain_
gain for external forces ("Penalty on low distance to abstacles") 
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan)
Set plan which shall be optimized to elastic band planner. 
std::string getGlobalFrameID()
int num_optim_iterations_
maximal number of iteration steps during optimization of band 
void setVisualization(boost::shared_ptr< EBandVisualization > eband_visual)
passes a reference to the eband visualization object which can be used to visualize the band optimiza...
bool calcBubbleDistance(geometry_msgs::Pose start_center_pose, geometry_msgs::Pose end_center_pose, double &distance)
This calculates the distance between two bubbles [depends kinematics, shape]. 
void Pose2DToPose(geometry_msgs::Pose &pose, const geometry_msgs::Pose2D pose2D)
Converts a frame of type Pose to type Pose2D (mainly -> conversion of orientation from euler angles t...
double significant_force_
percentage of old force for which a new force is considered significant when higher as this value ...
bool getBand(std::vector< Bubble > &elastic_band)
This outputs the elastic_band. 
bool suppressTangentialForces(int bubble_num, std::vector< Bubble > band, geometry_msgs::WrenchStamped &forces)
Calculates tangential portion of forces. 
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the elastic band class by accesing costmap and loading parameters. 
bool calcBubbleDifference(geometry_msgs::Pose start_center_pose, geometry_msgs::Pose end_center_pose, geometry_msgs::Twist &difference)
Calculates the difference between the pose of the center of two bubbles and outputs it as Twist (poin...
std::vector< geometry_msgs::Point > footprint_spec_
bool convertPlanToBand(std::vector< geometry_msgs::PoseStamped > plan, std::vector< Bubble > &band)
This converts a plan from a sequence of stamped poses into a band, a sequence of bubbles. Therefore it calculates distances to the surrounding obstacles and derives the expansion or radius of the bubble. 
unsigned char getCost(unsigned int mx, unsigned int my) const 
bool calcInternalForces(int bubble_num, std::vector< Bubble > band, Bubble curr_bubble, geometry_msgs::WrenchStamped &forces)
Calculates internal forces for bubbles along the band [depends kinematic]. 
bool moveApproximateEquilibrium(const int &bubble_num, const std::vector< Bubble > &band, Bubble &curr_bubble, const geometry_msgs::WrenchStamped &curr_bubble_force, geometry_msgs::Twist &curr_step_width, const int &curr_recursion_depth)
Checks for zero-crossings and large changes in force-vector after moving of bubble - if detected it t...
double distance(double x0, double y0, double x1, double y1)
~EBandPlanner()
Destructor. 
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
double getCircumscribedRadius(costmap_2d::Costmap2DROS &costmap)
Gets the footprint of the robot and computes the circumscribed radius for the eband approach...
EBandPlanner()
Default constructor. 
bool addFrames(const std::vector< geometry_msgs::PoseStamped > &robot_pose, const AddAtPosition &add_frames_at)
converts robot_pose to a bubble and tries to connect to the path 
bool removeAndFill(std::vector< Bubble > &band, std::vector< Bubble >::iterator &start_iter, std::vector< Bubble >::iterator &end_iter)
recursively checks an intervall of a band whether gaps need to be filled or bubbles may be removed an...
double min_bubble_overlap_
minimum relative overlap two bubbles must have to be treated as connected 
bool applyForces(int bubble_num, std::vector< Bubble > &band, std::vector< geometry_msgs::WrenchStamped > forces)
Applies forces to move bubbles and recalculates expansion of bubbles. 
bool optimizeBand()
cycles over the elastic band set before and optimizes it locally by minimizing an energy-function ...
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
def normalize_angle(angle)
bool calcExternalForces(int bubble_num, Bubble curr_bubble, geometry_msgs::WrenchStamped &forces)
Calculates external forces for bubbles along the band [depends shape, environment]. 
double costmap_weight_
lower bound for absolute value of force below which it is treated as insignificant (no recursive appr...
double tiny_bubble_expansion_
lower bound for bubble expansion. below this bound bubble is considered as "in collision" ...
static const unsigned char LETHAL_OBSTACLE
bool refineBand(std::vector< Bubble > &band)
Cycles over an band and searches for gaps and redundant bubbles. Tries to close gaps and remove redun...
TFSIMD_FORCE_INLINE tfScalar distance2(const Vector3 &v) const 
void reconfigure(EBandPlannerConfig &config)
Reconfigures the parameters of the planner. 
geometry_msgs::PoseStamped center
bool getForcesAt(int bubble_num, std::vector< Bubble > band, Bubble curr_bubble, geometry_msgs::WrenchStamped &forces)
Calculates all forces for a certain bubble at a specific position in the band [depends kinematic]...
std::vector< geometry_msgs::Point > getRobotFootprint()
costmap_2d::Costmap2DROS * costmap_ros_
pointer to costmap 
double tiny_bubble_distance_
internal forces between two bubbles are only calc. if there distance is bigger than this lower bound ...
bool fillGap(std::vector< Bubble > &band, std::vector< Bubble >::iterator &start_iter, std::vector< Bubble >::iterator &end_iter)
recursively fills gaps between two bubbles (if possible) 
bool modifyBandArtificialForce(std::vector< Bubble > &band)
calculates internal and external forces and applies changes to the band 
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const 
boost::shared_ptr< EBandVisualization > eband_visual_
base_local_planner::CostmapModel * world_model_
void PoseToPose2D(const geometry_msgs::Pose pose, geometry_msgs::Pose2D &pose2D)
Converts a frame of type Pose to type Pose2D (mainly -> conversion of orientation from quaternions to...
bool checkOverlap(Bubble bubble1, Bubble bubble2)
this checks whether two bubbles overlap 
int max_recursion_depth_approx_equi_
bool calcObstacleKinematicDistance(geometry_msgs::Pose center_pose, double &distance)
Calculates the distance between the center of a bubble and the closest obstacle [depends kinematics...