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
4140SerestController::SerestController () = default ;
4241SerestController::~SerestController () = default ;
4342
44- std::expected< void , std::string>
43+ void
4544SerestController::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
156153SerestController::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