Skip to content

Commit ebba4f7

Browse files
refactor(common, control, planning): replace boost::optional with std::optional (#5717)
* refactor(behavior_path_planner): replace boost optional with std Signed-off-by: Muhammad Zulfaqar <zulfaqar.azmi@tier4.jp> * do it on motion utils as well. Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * up until now Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * finally Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix all issue Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Muhammad Zulfaqar <zulfaqar.azmi@tier4.jp> Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent fd58f69 commit ebba4f7

File tree

93 files changed

+910
-905
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

93 files changed

+910
-905
lines changed

common/motion_utils/include/motion_utils/distance/distance.hpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -15,17 +15,16 @@
1515
#ifndef MOTION_UTILS__DISTANCE__DISTANCE_HPP_
1616
#define MOTION_UTILS__DISTANCE__DISTANCE_HPP_
1717

18-
#include <boost/optional.hpp>
19-
2018
#include <algorithm>
2119
#include <cmath>
2220
#include <iostream>
21+
#include <optional>
2322
#include <tuple>
2423
#include <vector>
2524

2625
namespace motion_utils
2726
{
28-
boost::optional<double> calcDecelDistWithJerkAndAccConstraints(
27+
std::optional<double> calcDecelDistWithJerkAndAccConstraints(
2928
const double current_vel, const double target_vel, const double current_acc, const double acc_min,
3029
const double jerk_acc, const double jerk_dec);
3130

common/motion_utils/include/motion_utils/trajectory/interpolation.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -21,10 +21,9 @@
2121
#include "autoware_auto_planning_msgs/msg/path_with_lane_id.hpp"
2222
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
2323

24-
#include <boost/optional.hpp>
25-
2624
#include <algorithm>
2725
#include <limits>
26+
#include <optional>
2827
#include <stdexcept>
2928
#include <vector>
3029

common/motion_utils/include/motion_utils/trajectory/path_with_lane_id.hpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -18,12 +18,11 @@
1818
#include "autoware_auto_planning_msgs/msg/path_with_lane_id.hpp"
1919
#include <geometry_msgs/msg/point.hpp>
2020

21-
#include <boost/optional.hpp>
22-
21+
#include <optional>
2322
#include <utility>
2423
namespace motion_utils
2524
{
26-
boost::optional<std::pair<size_t, size_t>> getPathIndexRangeWithLaneId(
25+
std::optional<std::pair<size_t, size_t>> getPathIndexRangeWithLaneId(
2726
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const int64_t target_lane_id);
2827

2928
size_t findNearestIndexFromLaneId(

common/motion_utils/include/motion_utils/trajectory/trajectory.hpp

+111-108
Large diffs are not rendered by default.

common/motion_utils/src/distance/distance.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,7 @@ std::tuple<double, double, double> update(
9191
* @param (t_during_min_acc) duration of constant deceleration [s]
9292
* @return moving distance until velocity is reached vt [m]
9393
*/
94-
boost::optional<double> calcDecelDistPlanType1(
94+
std::optional<double> calcDecelDistPlanType1(
9595
const double v0, const double vt, const double a0, const double am, const double ja,
9696
const double jd, const double t_during_min_acc)
9797
{
@@ -155,7 +155,7 @@ boost::optional<double> calcDecelDistPlanType1(
155155
* @param (jd) minimum jerk [m/sss]
156156
* @return moving distance until velocity is reached vt [m]
157157
*/
158-
boost::optional<double> calcDecelDistPlanType2(
158+
std::optional<double> calcDecelDistPlanType2(
159159
const double v0, const double vt, const double a0, const double ja, const double jd)
160160
{
161161
constexpr double epsilon = 1e-3;
@@ -212,7 +212,7 @@ boost::optional<double> calcDecelDistPlanType2(
212212
* @param (ja) maximum jerk [m/sss]
213213
* @return moving distance until velocity is reached vt [m]
214214
*/
215-
boost::optional<double> calcDecelDistPlanType3(
215+
std::optional<double> calcDecelDistPlanType3(
216216
const double v0, const double vt, const double a0, const double ja)
217217
{
218218
constexpr double epsilon = 1e-3;
@@ -234,7 +234,7 @@ boost::optional<double> calcDecelDistPlanType3(
234234
}
235235
} // namespace
236236

237-
boost::optional<double> calcDecelDistWithJerkAndAccConstraints(
237+
std::optional<double> calcDecelDistWithJerkAndAccConstraints(
238238
const double current_vel, const double target_vel, const double current_acc, const double acc_min,
239239
const double jerk_acc, const double jerk_dec)
240240
{

common/motion_utils/src/trajectory/path_with_lane_id.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424
namespace motion_utils
2525
{
2626

27-
boost::optional<std::pair<size_t, size_t>> getPathIndexRangeWithLaneId(
27+
std::optional<std::pair<size_t, size_t>> getPathIndexRangeWithLaneId(
2828
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const int64_t target_lane_id)
2929
{
3030
size_t start_idx = 0; // NOTE: to prevent from maybe-uninitialized error

common/motion_utils/src/trajectory/trajectory.cpp

+52-52
Large diffs are not rendered by default.

common/motion_utils/src/vehicle/vehicle_state_checker.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,7 @@ bool VehicleArrivalChecker::isVehicleStoppedAtStopPoint(const double stop_durati
124124
return false;
125125
}
126126

127-
return std::abs(motion_utils::calcSignedArcLength(trajectory_ptr_->points, p, idx.get())) <
127+
return std::abs(motion_utils::calcSignedArcLength(trajectory_ptr_->points, p, idx.value())) <
128128
th_arrived_distance_m;
129129
}
130130

common/motion_utils/test/src/trajectory/test_path_with_lane_id.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -85,15 +85,15 @@ TEST(path_with_lane_id, getPathIndexRangeWithLaneId)
8585
}
8686
{
8787
const auto res = getPathIndexRangeWithLaneId(points, 4);
88-
EXPECT_EQ(res, boost::none);
88+
EXPECT_EQ(res, std::nullopt);
8989
}
9090
}
9191

9292
// Empty points
9393
{
9494
PathWithLaneId points;
9595
const auto res = getPathIndexRangeWithLaneId(points, 4);
96-
EXPECT_EQ(res, boost::none);
96+
EXPECT_EQ(res, std::nullopt);
9797
}
9898
}
9999

0 commit comments

Comments
 (0)