AP_L1_Controller: add accessor for xtrack_error_integrator
This commit is contained in:
parent
85913bd237
commit
2ce964c8ac
@ -109,11 +109,6 @@ bool AP_L1_Control::reached_loiter_target(void)
|
||||
return _WPcircle;
|
||||
}
|
||||
|
||||
float AP_L1_Control::crosstrack_error(void) const
|
||||
{
|
||||
return _crosstrack_error;
|
||||
}
|
||||
|
||||
/**
|
||||
prevent indecision in our turning by using our previous turn
|
||||
decision if we are in a narrow angle band pointing away from the
|
||||
|
@ -38,7 +38,8 @@ public:
|
||||
// return the heading error angle (centi-degrees) +ve to left of track
|
||||
int32_t bearing_error_cd(void) const;
|
||||
|
||||
float crosstrack_error(void) const;
|
||||
float crosstrack_error(void) const { return _crosstrack_error; }
|
||||
float crosstrack_error_integrator(void) const { return _L1_xtrack_i; }
|
||||
|
||||
int32_t target_bearing_cd(void) const;
|
||||
float turn_distance(float wp_radius) const;
|
||||
|
@ -45,7 +45,9 @@ public:
|
||||
|
||||
// return the crosstrack error in meters. This is the distance in
|
||||
// the X-Y plane that we are off the desired track
|
||||
virtual float crosstrack_error(void) const = 0;
|
||||
virtual float crosstrack_error(void) const = 0;
|
||||
virtual float crosstrack_error_integrator(void) const { return 0; }
|
||||
|
||||
|
||||
// return the distance in meters at which a turn should commence
|
||||
// to allow the vehicle to neatly move to the next track in the
|
||||
|
Loading…
Reference in New Issue
Block a user