Skip to content

Commit 925c3df

Browse files
committed
Translate comments
Signed-off-by: Francisco Martín Rico <fmrico@gmail.com>
1 parent 6d6d06a commit 925c3df

1 file changed

Lines changed: 32 additions & 32 deletions

File tree

controllers/easynav_serest_controller/src/easynav_serest_controller/SerestController.cpp

Lines changed: 32 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ SerestController::on_initialize()
4646
auto node = get_node();
4747
const auto & ns = get_plugin_name();
4848

49-
// Máximos y límites básicos
49+
// Maximums and basic limits
5050
node->declare_parameter<bool>(ns + ".allow_reverse", allow_reverse_);
5151
node->declare_parameter<double>(ns + ".v_progress_min", v_progress_min_);
5252
node->declare_parameter<double>(ns + ".k_s_share_max", k_s_share_max_);
@@ -56,15 +56,15 @@ SerestController::on_initialize()
5656
node->declare_parameter<double>(ns + ".max_linear_acc", max_linear_acc_);
5757
node->declare_parameter<double>(ns + ".max_angular_acc", max_angular_acc_);
5858

59-
// Seguimiento
59+
// Tracking
6060
node->declare_parameter<double>(ns + ".k_s", k_s_);
6161
node->declare_parameter<double>(ns + ".k_theta", k_theta_);
6262
node->declare_parameter<double>(ns + ".k_y", k_y_);
6363
node->declare_parameter<double>(ns + ".ell", ell_);
6464
node->declare_parameter<double>(ns + ".v_ref", v_ref_);
6565
node->declare_parameter<double>(ns + ".eps", eps_);
6666

67-
// Seguridad
67+
// Safety
6868
node->declare_parameter<double>(ns + ".a_acc", a_acc_);
6969
node->declare_parameter<double>(ns + ".a_brake", a_brake_);
7070
node->declare_parameter<double>(ns + ".a_lat_max", a_lat_max_);
@@ -73,7 +73,7 @@ SerestController::on_initialize()
7373
node->declare_parameter<double>(ns + ".d_hard", d_hard_);
7474
node->declare_parameter<double>(ns + ".t_emerg", t_emerg_);
7575

76-
// Blend en vértices
76+
// Blend at vertices
7777
node->declare_parameter<double>(ns + ".blend_base", blend_base_);
7878
node->declare_parameter<double>(ns + ".blend_k_per_v", blend_k_per_v_);
7979
node->declare_parameter<double>(ns + ".kappa_max", kappa_max_);
@@ -219,29 +219,29 @@ SerestController::ref_heading_and_curvature(
219219
};
220220
auto atan2dir = [](const Vec2 & t){return std::atan2(t.y, t.x);};
221221

222-
// Índices de segmentos relevante: i-1, i, i + 1
222+
// Relevant segment indices: i-1, i, i + 1
223223
const size_t i = prj.seg_idx;
224224
const Vec2 Ti = seg_dir(i);
225225
double psi_i = atan2dir(Ti);
226226

227-
// Mezcla local con previsualización
227+
// Local blend with look-ahead
228228
double b = std::max(0.1, blend_base_ + blend_k_per_v_ * std::fabs(v_prev));
229229

230-
// Determina si estamos cerca del comienzo o fin de un segmento
230+
// Determine if we are near the beginning or end of a segment
231231
double s_i = pd.s_acc[i];
232232
double s_ip1 = pd.s_acc[i + 1];
233233
double s = prj.s_star;
234234

235-
// Por defecto: rumbo constante del segmento, kappa = 0
235+
// Default: constant segment heading, kappa = 0
236236
rk.psi_ref = psi_i;
237237
rk.kappa_hat = 0.0;
238238

239-
// Blend cerca del inicio del segmento i (con i-1)
239+
// Blend near the beginning of segment i (with i-1)
240240
if (i > 0 && (s - s_i) < b) {
241241
Vec2 Tim1 = seg_dir(i - 1);
242242
double psi_im1 = atan2dir(Tim1);
243-
double w = 1.0 / (1.0 + std::exp(-( (s - s_i) / b ))); // sigmoide en [s_i, s_i+b]
244-
// Interpolación circular de rumbos
243+
double w = 1.0 / (1.0 + std::exp(-( (s - s_i) / b ))); // sigmoid in [s_i, s_i+b]
244+
// Circular interpolation of headings
245245
double sx = (1.0 - w) * std::cos(psi_im1) + w * std::cos(psi_i);
246246
double sy = (1.0 - w) * std::sin(psi_im1) + w * std::sin(psi_i);
247247
rk.psi_ref = std::atan2(sy, sx);
@@ -252,20 +252,20 @@ SerestController::ref_heading_and_curvature(
252252
rk.kappa_hat = std::clamp(dpsi * sigma_prime, -kappa_max_, kappa_max_);
253253
}
254254

255-
// Blend cerca del final del segmento i (hacia i + 1)
255+
// Blend near the end of segment i (towards i + 1)
256256
if (i + 1 < pd.pts.size() - 1 && (s_ip1 - s) < b) {
257257
Vec2 Tip1 = seg_dir(i + 1);
258258
double psi_ip1 = atan2dir(Tip1);
259-
double w = 1.0 / (1.0 + std::exp(-( (s_ip1 - s) / b ))); // simétrico
260-
// Mezcla entre i y i + 1
259+
double w = 1.0 / (1.0 + std::exp(-( (s_ip1 - s) / b ))); // symmetric
260+
// Blend between i and i + 1
261261
double sx = (1.0 - w) * std::cos(psi_i) + w * std::cos(psi_ip1);
262262
double sy = (1.0 - w) * std::sin(psi_i) + w * std::sin(psi_ip1);
263263
rk.psi_ref = std::atan2(sy, sx);
264264

265265
double dpsi = std::atan2(std::sin(psi_ip1 - psi_i), std::cos(psi_ip1 - psi_i));
266266
double sigma_prime = (w * (1 - w)) / b;
267267
double kappa2 = std::clamp(dpsi * sigma_prime, -kappa_max_, kappa_max_);
268-
// Si hay dos blends solapados, combinamos suavemente (promedio)
268+
// If there are two overlapping blends, combine smoothly (average)
269269
rk.kappa_hat = 0.5 * (rk.kappa_hat + kappa2);
270270
}
271271

@@ -278,29 +278,29 @@ SerestController::frenet_errors(
278278
const Projection & prj, double psi_ref,
279279
double & e_y, double & e_theta) const
280280
{
281-
// Vector normal a la derecha de la tangente
281+
// Normal vector to the right of the tangent
282282
Vec2 T = v2(std::cos(psi_ref), std::sin(psi_ref));
283-
Vec2 N = v2(-T.y, T.x); // 90º a la izquierda (convención)
283+
Vec2 N = v2(-T.y, T.x); // 90º to the left (convention)
284284
Vec2 err = robot_xy - prj.closest;
285285

286-
e_y = dot(err, N); // distancia lateral con signo
286+
e_y = dot(err, N); // signed lateral distance
287287
e_theta = std::atan2(std::sin(robot_yaw - psi_ref), std::cos(robot_yaw - psi_ref));
288288
}
289289

290290
double
291291
SerestController::closest_obstacle_distance(
292292
const NavState & nav_state) const
293293
{
294-
// 1) Preferir medición directa si existe
294+
// 1) Prefer direct measurement if it exists
295295
if (nav_state.has("closest_obstacle_distance")) {
296296
try {
297297
return nav_state.get<double>("closest_obstacle_distance");
298298
} catch (...) {
299-
// continúa a estimación
299+
// fall through to estimation
300300
}
301301
}
302302

303-
// 2) Analizar los sensores de distancia
303+
// 2) Analyze distance sensors
304304
if (!nav_state.has("points")) {return std::numeric_limits<double>::infinity();}
305305

306306
const auto & perceptions = nav_state.get<PointPerceptions>("points");
@@ -325,7 +325,7 @@ SerestController::closest_obstacle_distance(
325325
double
326326
SerestController::v_safe_from_distance(double d, double slope_sin) const
327327
{
328-
// a_eff reduce la capacidad de frenado en pendiente; en 2D slope_sin = 0
328+
// a_eff reduces braking capability on slopes; in 2D slope_sin = 0
329329
const double a_eff = std::max(0.1, a_brake_ - 9.81 * slope_sin);
330330
if (d <= d0_margin_) {return 0.0;}
331331

@@ -338,7 +338,7 @@ SerestController::v_safe_from_distance(double d, double slope_sin) const
338338
double
339339
SerestController::v_curvature_limit(double kappa_hat) const
340340
{
341-
// Tres límites típicos: v_max, ω_max/|κ| y sqrt(a_lat_max/|κ|)
341+
// Three typical limits: v_max, ω_max/|κ| and sqrt(a_lat_max/|κ|)
342342
double v1 = max_linear_speed_;
343343
double v2 = std::numeric_limits<double>::infinity();
344344
double v3 = std::numeric_limits<double>::infinity();
@@ -430,7 +430,7 @@ SerestController::safety_limits(
430430
d_closest = closest_obstacle_distance(nav_state);
431431
v_safe = v_safe_from_distance(d_closest, /*slope_sin=*/0.0);
432432

433-
// Límite por curvatura (versión “soft” del archivo original)
433+
// Curvature-based limit ("soft" version of the original file)
434434
const double ak = std::fabs(rk.kappa_hat);
435435
double v_curv_soft = std::numeric_limits<double>::infinity();
436436
if (ak > 1e-6) {
@@ -465,7 +465,7 @@ SerestController::apply_corner_guard(
465465
alpha_corner = std::clamp(1.0 / (1.0 + penal), corner_min_alpha_, 1.0);
466466
omega_boost = 1.0 + corner_boost_omega_ * std::min(1.0, e_y_out / std::max(1e-3, ell_));
467467

468-
// Empuje al “ápice” si vas por fuera y hay curvatura
468+
// Push towards the "apex" if you are outside and there is curvature
469469
if (std::fabs(rk.kappa_hat) > 1e-6 && e_y_out > 0.0) {
470470
const double e_y_des = -sgn_k * std::max(0.0, apex_ey_des_);
471471
const double e_y_err = e_y - e_y_des;
@@ -480,16 +480,16 @@ SerestController::should_turn_in_place(
480480
bool allow_reverse, double e_theta, double e_theta_goal,
481481
double dist_to_end, [[maybe_unused]] double turn_in_place_thr) const
482482
{
483-
// Mantenemos compatibilidad con la firma, pero ignoramos turn_in_place_thr
484-
// y usamos dos umbrales internos sin exponer parámetros.
485-
const double thr_enter = 60.0 * std::numbers::pi / 180.0; // entra a girar si |e_theta| > 60°
486-
// const double thr_exit = 35.0 * PI / 180.0; // sale de girar si |e_theta| < 35°
483+
// Keep compatibility with the signature, but ignore turn_in_place_thr
484+
// and use two internal thresholds without exposing parameters.
485+
const double thr_enter = 60.0 * std::numbers::pi / 180.0; // enter TiP if |e_theta| > 60°
486+
// const double thr_exit = 35.0 * PI / 180.0; // exit TiP if |e_theta| < 35°
487487

488-
// No permitimos “atajo” marcha atrás en esta decisión: si no permites reverse,
489-
// el criterio es más estricto.
488+
// Do not allow reverse "shortcut" in this decision: if reverse is not allowed,
489+
// the criterion is stricter.
490490
bool tip = (!allow_reverse) && (std::fabs(e_theta) > thr_enter);
491491

492-
// Cerca del final, si el yaw al objetivo es grande, también pedimos TiP
492+
// Near the end, if the yaw error to the goal is large, also request TiP
493493
if (dist_to_end < 0.50) {
494494
if (!allow_reverse && std::fabs(e_theta_goal) > thr_enter) {
495495
tip = true;

0 commit comments

Comments
 (0)