Skip to content

Commit

Permalink
Update ros-noetic-teb-local-planner.osx.patch
Browse files Browse the repository at this point in the history
  • Loading branch information
Tobias-Fischer authored Jan 31, 2024
1 parent 301cb73 commit aa5267b
Showing 1 changed file with 54 additions and 0 deletions.
54 changes: 54 additions & 0 deletions patch/ros-noetic-teb-local-planner.osx.patch
Original file line number Diff line number Diff line change
@@ -1,3 +1,57 @@
diff --git a/include/teb_local_planner/timed_elastic_band.hpp b/include/teb_local_planner/timed_elastic_band.hpp
index 66c92b8..8a95eaf 100644
--- a/include/teb_local_planner/timed_elastic_band.hpp
+++ b/include/teb_local_planner/timed_elastic_band.hpp
@@ -36,6 +36,7 @@
* Author: Christoph Rösmann
*********************************************************************/

+#include <iterator>
#include <teb_local_planner/timed_elastic_band.h>

namespace teb_local_planner
@@ -49,7 +50,7 @@ bool TimedElasticBand::initTrajectoryToGoal(BidirIter path_start, BidirIter path
boost::optional<double> start_orientation, boost::optional<double> goal_orientation, int min_samples, bool guess_backwards_motion)
{
Eigen::Vector2d start_position = fun_position( *path_start );
- Eigen::Vector2d goal_position = fun_position( *boost::prior(path_end) );
+ Eigen::Vector2d goal_position = fun_position( *std::prev(path_end) );

bool backwards = false;

diff --git a/include/teb_local_planner/visualization.hpp b/include/teb_local_planner/visualization.hpp
index e619e52..548c57a 100644
--- a/include/teb_local_planner/visualization.hpp
+++ b/include/teb_local_planner/visualization.hpp
@@ -38,6 +38,7 @@

#include <teb_local_planner/visualization.h>
#include <boost/utility.hpp>
+#include <iterator>


namespace teb_local_planner
@@ -196,7 +197,7 @@ void TebVisualization::publishPathContainer(BidirIter first, BidirIter last, con
{
// iterate single path points
typename PathType::const_iterator it_point, end_point;
- for (it_point = first->begin(), end_point = boost::prior(first->end()); it_point != end_point; ++it_point)
+ for (it_point = first->begin(), end_point = std::prev(first->end()); it_point != end_point; ++it_point)
{
geometry_msgs::Point point_start;
point_start.x = get_const_reference(*it_point).x();
@@ -205,8 +206,8 @@ void TebVisualization::publishPathContainer(BidirIter first, BidirIter last, con
marker.points.push_back(point_start);

geometry_msgs::Point point_end;
- point_end.x = get_const_reference(*boost::next(it_point)).x();
- point_end.y = get_const_reference(*boost::next(it_point)).y();
+ point_end.x = get_const_reference(*std::next(it_point)).x();
+ point_end.y = get_const_reference(*std::next(it_point)).y();
point_end.z = 0;
marker.points.push_back(point_end);
}

diff --git a/include/teb_local_planner/h_signature.h b/include/teb_local_planner/h_signature.h
index 8837950..4cffcda 100644
--- a/include/teb_local_planner/h_signature.h
Expand Down

0 comments on commit aa5267b

Please sign in to comment.