Skip to content

Commit c70df1e

Browse files
Thomas StastnyJaeyoung-Lim
authored andcommitted
npfg: rearrange eval method, handle case in front of starting point of path segment
1 parent 4d11b4e commit c70df1e

File tree

2 files changed

+84
-35
lines changed

2 files changed

+84
-35
lines changed

src/lib/npfg/npfg.cpp

Lines changed: 74 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -47,8 +47,9 @@
4747
using matrix::Vector2d;
4848
using matrix::Vector2f;
4949

50-
void NPFG::evaluate(const Vector2f &ground_vel, const Vector2f &wind_vel,
51-
const Vector2f &unit_path_tangent, const float signed_track_error, const float path_curvature)
50+
void NPFG::evaluate(const Vector2f &ground_vel, const Vector2f &wind_vel, Vector2f &unit_path_tangent,
51+
float signed_track_error, const float path_curvature, bool in_front_of_wp /*= false*/,
52+
const Vector2f &bearing_vec_to_point /*= Vector2f{0.0f, 0.0f}*/)
5253
{
5354
const float ground_speed = ground_vel.norm();
5455

@@ -62,16 +63,18 @@ void NPFG::evaluate(const Vector2f &ground_vel, const Vector2f &wind_vel,
6263
airspeed_ref_ = airspeed_nom_;
6364
lateral_accel_ = 0.0f;
6465
feas_ = 0.0f;
66+
feas_on_track_ = 0.0f;
6567
return;
6668
}
6769

6870
const float wind_speed = wind_vel.norm();
6971
const float wind_ratio = wind_speed / airspeed;
7072

71-
const float track_error = fabsf(signed_track_error);
73+
float track_error = fabsf(signed_track_error);
7274

73-
const float wind_cross_upt = cross2D(wind_vel, unit_path_tangent);
74-
const float wind_dot_upt = wind_vel.dot(unit_path_tangent);
75+
// on-track wind triangle projections
76+
float wind_cross_upt = cross2D(wind_vel, unit_path_tangent);
77+
float wind_dot_upt = wind_vel.dot(unit_path_tangent);
7578

7679
// calculate the bearing feasibility on the track at the current closest point
7780
feas_on_track_ = bearingFeasibility(wind_cross_upt, wind_dot_upt, wind_speed, wind_ratio);
@@ -85,21 +88,55 @@ void NPFG::evaluate(const Vector2f &ground_vel, const Vector2f &wind_vel,
8588

8689
// track error bound is dynamic depending on ground speed
8790
track_error_bound_ = trackErrorBound(ground_speed, time_const_);
88-
const float normalized_track_error = normalizedTrackError(track_error, track_error_bound_);
91+
float normalized_track_error = normalizedTrackError(track_error, track_error_bound_);
8992

9093
// look ahead angle based purely on track proximity
91-
const float look_ahead_ang = lookAheadAngle(normalized_track_error);
94+
float look_ahead_ang = lookAheadAngle(normalized_track_error);
9295

9396
bearing_vec_ = bearingVec(unit_path_tangent, look_ahead_ang, signed_track_error);
9497

95-
float wind_cross_bearing = cross2D(wind_vel, bearing_vec_);
96-
float wind_dot_bearing = wind_vel.dot(bearing_vec_);
98+
// specific waypoint logic complications... handles case where we are following
99+
// waypoints and are in front of the first of the segment.
100+
// TODO: find a way to get this out of the main eval method!
101+
if (in_front_of_wp && unit_path_tangent.dot(bearing_vec_) < unit_path_tangent.dot(bearing_vec_to_point)) {
102+
// we are in front of the first waypoint and the bearing to the point is
103+
// shallower than that to the line. reset path params to fly directly to
104+
// the first waypoint.
105+
106+
// TODO: probably better to blend these instead of hard switching (could
107+
// effect the adaptive tuning if we switch between these cases with wind
108+
// gusts)
109+
110+
// pretend we are on track, recalculate necessary quantities
111+
112+
signed_track_error = 0.0f;
113+
normalized_track_error = 0.0f;
114+
unit_path_tangent = bearing_vec_to_point;
115+
116+
bearing_vec_ = bearing_vec_to_point;
117+
look_ahead_ang = 0.0f;
118+
119+
wind_cross_upt = cross2D(wind_vel, unit_path_tangent);
120+
wind_dot_upt = wind_vel.dot(unit_path_tangent);
121+
feas_on_track_ = bearingFeasibility(wind_cross_upt, wind_dot_upt, wind_speed, wind_ratio);
122+
123+
adapted_period_ = adaptPeriod(ground_speed, airspeed, wind_ratio, track_error,
124+
path_curvature, wind_vel, unit_path_tangent, feas_on_track_);
125+
p_gain_ = pGain(adapted_period_, damping_);
126+
time_const_ = timeConst(adapted_period_, damping_);
127+
}
128+
129+
track_proximity_ = trackProximity(look_ahead_ang);
130+
131+
// wind triangle projections
132+
const float wind_cross_bearing = cross2D(wind_vel, bearing_vec_);
133+
const float wind_dot_bearing = wind_vel.dot(bearing_vec_);
97134

98135
// continuous representation of the bearing feasibility
99136
feas_ = bearingFeasibility(wind_cross_bearing, wind_dot_bearing, wind_speed, wind_ratio);
100137

101138
// we consider feasibility of both the current bearing as well as that on the track at the current closest point
102-
float feas_combined = feas_ * feas_on_track_;
139+
const float feas_combined = feas_ * feas_on_track_;
103140

104141
min_ground_speed_ref_ = minGroundSpeed(normalized_track_error, feas_combined);
105142

@@ -110,16 +147,18 @@ void NPFG::evaluate(const Vector2f &ground_vel, const Vector2f &wind_vel,
110147
wind_dot_bearing, wind_speed, min_ground_speed_ref_);
111148
airspeed_ref_ = air_vel_ref_.norm();
112149

113-
track_proximity_ = trackProximity(look_ahead_ang);
150+
// lateral acceleration demand based on heading error
151+
const float lateral_accel = lateralAccel(air_vel, air_vel_ref_, airspeed);
114152

115153
// lateral acceleration needed to stay on curved track (assuming no heading error)
116-
lateral_accel_ff_ = lateralAccelFF(unit_path_tangent, ground_vel,
117-
wind_dot_upt, wind_cross_upt, airspeed, wind_speed, wind_ratio,
118-
signed_track_error, path_curvature, track_proximity_, feas_combined);
154+
lateral_accel_ff_ = lateralAccelFF(unit_path_tangent, ground_vel, wind_dot_upt,
155+
wind_cross_upt, airspeed, wind_speed, wind_ratio, signed_track_error, path_curvature);
119156

120157
// total lateral acceleration to drive aircaft towards track as well as account
121-
// for path curvature
122-
lateral_accel_ = lateralAccel(air_vel, air_vel_ref_, airspeed) + lateral_accel_ff_;
158+
// for path curvature. The full effect of the feed-forward acceleration is smoothly
159+
// ramped in as the vehicle approaches the track and is further smoothly
160+
// zeroed out as the bearing becomes infeasible.
161+
lateral_accel_ = lateral_accel + feas_combined * track_proximity_ * lateral_accel_ff_;
123162
} // evaluate
124163

125164
float NPFG::adaptPeriod(const float ground_speed, const float airspeed, const float wind_ratio,
@@ -431,14 +470,14 @@ float NPFG::bearingFeasibility(const float wind_cross_bearing, const float wind_
431470
float NPFG::lateralAccelFF(const Vector2f &unit_path_tangent, const Vector2f &ground_vel,
432471
const float wind_dot_upt, const float wind_cross_upt, const float airspeed,
433472
const float wind_speed, const float wind_ratio, const float signed_track_error,
434-
const float path_curvature, const float track_proximity, const float feas) const
473+
const float path_curvature) const
435474
{
436475
// NOTE: all calculations within this function take place at the closet point
437476
// on the path, as if the aircraft were already tracking the given path at
438477
// this point with zero angular error. this allows us to evaluate curvature
439478
// induced requirements for lateral acceleration incrementation and ramp them
440-
// in with the track proximity. further the bearing feasibility is considered
441-
// in excess wind conditions.
479+
// in with the track proximity and further consider the bearing feasibility
480+
// in excess wind conditions (this is done external to this method).
442481

443482
// path frame curvature is the instantaneous curvature at our current distance
444483
// from the actual path (considering e.g. concentric circles emanating outward/inward)
@@ -457,7 +496,7 @@ float NPFG::lateralAccelFF(const Vector2f &unit_path_tangent, const Vector2f &gr
457496
// note the use of airspeed * speed_ratio as oppose to ground_speed^2 here --
458497
// the prior considers that we command lateral acceleration in the air mass
459498
// relative frame while the latter does not
460-
return airspeed * track_proximity * feas * speed_ratio * path_frame_rate;
499+
return airspeed * speed_ratio * path_frame_rate;
461500
} // lateralAccelFF
462501

463502
float NPFG::lateralAccel(const Vector2f &air_vel, const Vector2f &air_vel_ref, const float airspeed) const
@@ -486,27 +525,36 @@ void NPFG::navigateWaypoints(const Vector2d &waypoint_A, const Vector2d &waypoin
486525
const Vector2d &vehicle_pos, const Vector2f &ground_vel, const Vector2f &wind_vel)
487526
{
488527
// similar to logic found in ECL_L1_Pos_Controller method of same name
528+
// BUT no arbitrary max approach angle, approach entirely determined by generated
529+
// bearing vectors
489530

490531
path_type_loiter_ = false;
491532

492533
Vector2f vector_A_to_B = getLocalPlanarVector(waypoint_A, waypoint_B);
493534
Vector2f vector_A_to_vehicle = getLocalPlanarVector(waypoint_A, vehicle_pos);
494535

495-
if (vector_A_to_B.norm() < EPSILON || vector_A_to_B.dot(vector_A_to_vehicle) < 0.0f) {
496-
// the waypoints are either on top of each other and should be considered
497-
// as single waypoint, or we are in front of waypoint A. in either case,
498-
// fly directly to A.
536+
if (vector_A_to_B.norm() < EPSILON) {
537+
// the waypoints are on top of each other and should be considered as a
538+
// single waypoint, fly directly to it
499539
unit_path_tangent_ = -vector_A_to_vehicle.normalized();
500540
signed_track_error_ = 0.0f;
541+
evaluate(ground_vel, wind_vel, unit_path_tangent_, signed_track_error_, 0.0f);
542+
543+
} else if (vector_A_to_B.dot(vector_A_to_vehicle) < 0.0f) {
544+
// we are in front of waypoint A, fly directly to it until the bearing generated
545+
// to the line segement between A and B is shallower than that from the
546+
// bearing to the first waypoint (A).
547+
unit_path_tangent_ = vector_A_to_B.normalized();
548+
signed_track_error_ = cross2D(unit_path_tangent_, vector_A_to_vehicle);
549+
evaluate(ground_vel, wind_vel, unit_path_tangent_, signed_track_error_, 0.0f, true, -vector_A_to_vehicle.normalized());
501550

502551
} else {
503552
// track the line segment between A and B
504553
unit_path_tangent_ = vector_A_to_B.normalized();
505554
signed_track_error_ = cross2D(unit_path_tangent_, vector_A_to_vehicle);
555+
evaluate(ground_vel, wind_vel, unit_path_tangent_, signed_track_error_, 0.0f);
506556
}
507557

508-
evaluate(ground_vel, wind_vel, unit_path_tangent_, signed_track_error_, 0.0f);
509-
510558
updateRollSetpoint();
511559
} // navigateWaypoints
512560

src/lib/npfg/npfg.hpp

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -402,11 +402,17 @@ class NPFG
402402
* @param[in] unit_path_tangent Unit vector tangent to path at closest point
403403
* in direction of path
404404
* @param[in] signed_track_error Signed error to track at closest point (sign
405-
* determined by path normal direction) [m]
405+
* determined by path normal direction) [m]
406406
* @param[in] path_curvature Path curvature at closest point on track [m^-1]
407+
* @param[in] in_front_of_wp True if we are in front of the starting point of
408+
* a path segment
409+
* @param[in] bearing_vec_to_point Bearing vector to starting point of path
410+
* segment, if relevant
407411
*/
408412
void evaluate(const matrix::Vector2f &ground_vel, const matrix::Vector2f &wind_vel,
409-
const matrix::Vector2f &unit_path_tangent, const float signed_track_error, const float path_curvature);
413+
matrix::Vector2f &unit_path_tangent, float signed_track_error,
414+
const float path_curvature, bool in_front_of_wp = false,
415+
const matrix::Vector2f &bearing_vec_to_point = matrix::Vector2f{0.0f, 0.0f});
410416

411417
/*
412418
* Adapts the controller period considering user defined inputs, current flight
@@ -625,9 +631,7 @@ class NPFG
625631

626632
/*
627633
* Calculates an additional feed-forward lateral acceleration demand considering
628-
* the path curvature. The full effect of the acceleration increment is smoothly
629-
* ramped in as the vehicle approaches the track and is further smoothly
630-
* zeroed out as the bearing becomes infeasible.
634+
* the path curvature.
631635
*
632636
* @param[in] unit_path_tangent Unit vector tangent to path at closest point
633637
* in direction of path
@@ -639,15 +643,12 @@ class NPFG
639643
* @param[in] signed_track_error Signed error to track at closest point (sign
640644
* determined by path normal direction) [m]
641645
* @param[in] path_curvature Path curvature at closest point on track [m^-1]
642-
* @param[in] track_proximity Smoothing parameter based on vehicle proximity
643-
* to track with values between 0 (at track error boundary) and 1 (on track)
644-
* @param[in] feas Bearing feasibility
645646
* @return Feed-forward lateral acceleration command [m/s^2]
646647
*/
647648
float lateralAccelFF(const matrix::Vector2f &unit_path_tangent, const matrix::Vector2f &ground_vel,
648649
const float wind_dot_upt, const float wind_cross_upt, const float airspeed,
649650
const float wind_speed, const float wind_ratio, const float signed_track_error,
650-
const float path_curvature, const float track_proximity, const float feas) const;
651+
const float path_curvature) const;
651652

652653
/*
653654
* Calculates a lateral acceleration demand from the heading error.

0 commit comments

Comments
 (0)