Skip to content

Commit 63aa3e5

Browse files
authored
Merge pull request #42 from Butakus/downgrade_plugins_cpp23
Downgrade from C++20/C++23 features
2 parents b242113 + 50855f2 commit 63aa3e5

81 files changed

Lines changed: 149 additions & 329 deletions

File tree

Some content is hidden

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

common/easynav_costmap_common/include/easynav_costmap_common/costmap_2d.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@
4141
#include <cstring>
4242
#include <algorithm>
4343
#include <cmath>
44+
#include <climits>
4445
#include <vector>
4546
#include <mutex>
4647
#include "geometry_msgs/msg/point.hpp"

controllers/easynav_mpc_controller/CMakeLists.txt

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -5,10 +5,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
55
add_compile_options(-Wall -Wextra -Wpedantic)
66
endif()
77

8-
set(CMAKE_CXX_STANDARD 23)
9-
set(CMAKE_CXX_STANDARD_REQUIRED ON)
10-
set(CMAKE_CXX_EXTENSIONS OFF)
11-
128
find_package(ament_cmake REQUIRED)
139
find_package(easynav_common REQUIRED)
1410
find_package(easynav_core REQUIRED)

controllers/easynav_mpc_controller/include/easynav_mpc_controller/MPCController.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,8 +45,8 @@ class MPCController : public ControllerMethodBase
4545
~MPCController() override;
4646

4747
/// \brief Initializes parameters and MPC controller.
48-
/// \return std::expected<void, std::string> success or error message.
49-
std::expected<void, std::string> on_initialize() override;
48+
/// \throws std::runtime_error if initialization fails.
49+
void on_initialize() override;
5050

5151
/// \brief Updates the controller using the given NavState.
5252
/// \param nav_state Current navigation state, including odometry and planned path.

controllers/easynav_mpc_controller/src/easynav_mpc_controller/MPCController.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ MPCController::MPCController() {}
3232

3333
MPCController::~MPCController() = default;
3434

35-
std::expected<void, std::string>
35+
void
3636
MPCController::on_initialize()
3737
{
3838
auto node = get_node();
@@ -65,8 +65,6 @@ MPCController::on_initialize()
6565

6666
detection_pub_ =
6767
node->create_publisher<sensor_msgs::msg::PointCloud2>("/mpc/detection", 10);
68-
69-
return {};
7068
}
7169

7270
void

controllers/easynav_mppi_controller/CMakeLists.txt

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -5,10 +5,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
55
add_compile_options(-Wall -Wextra -Wpedantic)
66
endif()
77

8-
set(CMAKE_CXX_STANDARD 23)
9-
set(CMAKE_CXX_STANDARD_REQUIRED ON)
10-
set(CMAKE_CXX_EXTENSIONS OFF)
11-
128
find_package(ament_cmake REQUIRED)
139
find_package(easynav_common REQUIRED)
1410
find_package(easynav_core REQUIRED)

controllers/easynav_mppi_controller/include/easynav_mppi_controller/MPPIController.hpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,6 @@
88
#define EASYNAV_MPPI_CONTROLLER__MPPICONTROLLER_HPP_
99

1010
#include <memory>
11-
#include <expected>
1211
#include <string>
1312

1413
#include "geometry_msgs/msg/twist_stamped.hpp"
@@ -33,8 +32,8 @@ class MPPIController : public ControllerMethodBase
3332
~MPPIController() override;
3433

3534
/// \brief Initializes parameters and MPPI controller.
36-
/// \return std::expected<void, std::string> success or error message.
37-
std::expected<void, std::string> on_initialize() override;
35+
/// \throws std::runtime_error if initialization fails.
36+
void on_initialize() override;
3837

3938
/// \brief Updates the controller using the given NavState.
4039
/// \param nav_state Current navigation state, including odometry and planned path.

controllers/easynav_mppi_controller/src/easynav_mppi_controller/MPPIController.cpp

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -20,8 +20,6 @@
2020
/// \file
2121
/// \brief Implementation of the MPPIController class.
2222

23-
#include <expected>
24-
2523
#include "easynav_mppi_controller/MPPIController.hpp"
2624
#include "easynav_common/types/PointPerception.hpp"
2725
#include "easynav_common/RTTFBuffer.hpp"
@@ -37,7 +35,7 @@ MPPIController::MPPIController() {}
3735

3836
MPPIController::~MPPIController() = default;
3937

40-
std::expected<void, std::string>
38+
void
4139
MPPIController::on_initialize()
4240
{
4341
auto node = get_node();
@@ -72,8 +70,6 @@ MPPIController::on_initialize()
7270
node->create_publisher<visualization_msgs::msg::MarkerArray>("/mppi/candidates", 10);
7371
mppi_optimal_pub_ =
7472
node->create_publisher<visualization_msgs::msg::MarkerArray>("/mppi/optimal_path", 10);
75-
76-
return {};
7773
}
7874

7975
void MPPIController::publish_mppi_markers(

controllers/easynav_serest_controller/CMakeLists.txt

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -5,10 +5,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
55
add_compile_options(-Wall -Wextra -Wpedantic)
66
endif()
77

8-
set(CMAKE_CXX_STANDARD 23)
9-
set(CMAKE_CXX_STANDARD_REQUIRED ON)
10-
set(CMAKE_CXX_EXTENSIONS OFF)
11-
128
find_package(ament_cmake REQUIRED)
139
find_package(easynav_common REQUIRED)
1410
find_package(easynav_core REQUIRED)

controllers/easynav_serest_controller/include/easynav_serest_controller/SerestController.hpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,6 @@
2020
#ifndef EASYNAV_SEREST_CONTROLLER__SERESTCONTROLLER_HPP_
2121
#define EASYNAV_SEREST_CONTROLLER__SERESTCONTROLLER_HPP_
2222

23-
#include <expected>
2423
#include <vector>
2524
#include <string>
2625

@@ -63,9 +62,9 @@ class SerestController : public ControllerMethodBase
6362

6463
/**
6564
* @brief Initialize parameters and internal state.
66-
* @return std::expected<void, std::string> Empty on success; error message otherwise.
65+
* @throws std::runtime_error on initialization error.
6766
*/
68-
std::expected<void, std::string> on_initialize() override;
67+
void on_initialize() override;
6968

7069
/**
7170
* @brief Real-time control update (called ~20–30 Hz).

controllers/easynav_serest_controller/src/easynav_serest_controller/SerestController.cpp

Lines changed: 6 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,6 @@
2323
#include <algorithm>
2424
#include <limits>
2525
#include <cmath>
26-
#include <numbers>
2726

2827
#include "tf2/utils.hpp"
2928
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
@@ -41,7 +40,7 @@ namespace easynav
4140
SerestController::SerestController() = default;
4241
SerestController::~SerestController() = default;
4342

44-
std::expected<void, std::string>
43+
void
4544
SerestController::on_initialize()
4645
{
4746
auto node = get_node();
@@ -149,8 +148,6 @@ SerestController::on_initialize()
149148
last_vlin_ = 0.0;
150149
last_vrot_ = 0.0;
151150
last_update_ts_ = node->now();
152-
153-
return {};
154151
}
155152

156153
SerestController::PathData
@@ -487,7 +484,7 @@ SerestController::should_turn_in_place(
487484
{
488485
// Keep compatibility with the signature, but ignore turn_in_place_thr
489486
// and use two internal thresholds without exposing parameters.
490-
const double thr_enter = 60.0 * std::numbers::pi / 180.0; // enter TiP if |e_theta| > 60°
487+
const double thr_enter = 60.0 * M_PI / 180.0; // enter TiP if |e_theta| > 60°
491488
// const double thr_exit = 35.0 * PI / 180.0; // exit TiP if |e_theta| < 35°
492489

493490
// Do not allow reverse "shortcut" in this decision: if reverse is not allowed,
@@ -510,7 +507,7 @@ SerestController::maybe_final_align_and_publish(
510507
double dist_xy_goal, double stop_r, double e_theta_goal,
511508
double gamma_slow, double dt)
512509
{
513-
const double goal_yaw_tol = goal_yaw_tol_deg_ * std::numbers::pi / 180.0;
510+
const double goal_yaw_tol = goal_yaw_tol_deg_ * M_PI / 180.0;
514511

515512
if (dist_xy_goal > stop_r) {
516513
return false;
@@ -625,7 +622,7 @@ SerestController::update_rt(NavState & nav_state)
625622

626623
// 1.5) Goal tolerances: prefer shared GoalManager values, fallback to local params
627624
double goal_pos_tol = goal_pos_tol_;
628-
double goal_yaw_tol = goal_yaw_tol_deg_ * (std::numbers::pi / 180.0);
625+
double goal_yaw_tol = goal_yaw_tol_deg_ * (M_PI / 180.0);
629626
if (nav_state.has("goal_tolerance.position")) {
630627
goal_pos_tol = nav_state.get<double>("goal_tolerance.position");
631628
}
@@ -727,7 +724,7 @@ SerestController::update_rt(NavState & nav_state)
727724
double v_prog_ref = v_prog_ref_free * gamma_slow;
728725

729726
// Maintain a small cruising speed when roughly aligned and outside the stop zone (no reverse)
730-
const double align_thr = 30.0 * std::numbers::pi / 180.0;
727+
const double align_thr = 30.0 * M_PI / 180.0;
731728
if (!allow_reverse_ && (dist_xy_goal > stop_r) && std::fabs(e_theta) < align_thr) {
732729
v_prog_ref = std::max(v_prog_ref, std::min(slow_min_speed_, v_prog_ref_free));
733730
}
@@ -778,7 +775,7 @@ SerestController::update_rt(NavState & nav_state)
778775

779776
// Optional classic TiP safeguard using the same angular threshold
780777
{
781-
const double turn_in_place_thr = (60.0 * std::numbers::pi / 180.0);
778+
const double turn_in_place_thr = (60.0 * M_PI / 180.0);
782779
const double s_total = pd.s_acc.back();
783780
const double dist_to_end = s_total - prj.s_star;
784781

0 commit comments

Comments
 (0)