mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
L1_Control: cleanup some unused code and variables
This commit is contained in:
parent
a423d102e0
commit
571c48b9d5
@ -81,10 +81,10 @@ void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct
|
|||||||
const float omegaA = 4.4428f/_L1_period; // sqrt(2)*pi/period
|
const float omegaA = 4.4428f/_L1_period; // sqrt(2)*pi/period
|
||||||
// Calculate additional damping gain
|
// Calculate additional damping gain
|
||||||
const float Kv = omegaA * 2.8284f * (_L1_damping - 0.7071f); // omegaA * 2*sqrt(2) * (dampingRatio - 1/sqrt(2))
|
const float Kv = omegaA * 2.8284f * (_L1_damping - 0.7071f); // omegaA * 2*sqrt(2) * (dampingRatio - 1/sqrt(2))
|
||||||
|
|
||||||
float Nu;
|
float Nu;
|
||||||
float dampingWeight;
|
float dampingWeight;
|
||||||
float xtrackVel;
|
float xtrackVel;
|
||||||
|
struct Location _current_loc;
|
||||||
|
|
||||||
// Get current position and velocity
|
// Get current position and velocity
|
||||||
_ahrs->get_position(&_current_loc);
|
_ahrs->get_position(&_current_loc);
|
||||||
@ -178,6 +178,7 @@ void AP_L1_Control::update_loiter(const struct Location ¢er_WP, float radius
|
|||||||
float omega = (6.2832f / _L1_period);
|
float omega = (6.2832f / _L1_period);
|
||||||
float Kx = omega * omega;
|
float Kx = omega * omega;
|
||||||
float Kv = 2.0f * _L1_damping * omega;
|
float Kv = 2.0f * _L1_damping * omega;
|
||||||
|
struct Location _current_loc;
|
||||||
|
|
||||||
//Get current position and velocity
|
//Get current position and velocity
|
||||||
_ahrs->get_position(&_current_loc);
|
_ahrs->get_position(&_current_loc);
|
||||||
@ -308,7 +309,7 @@ void AP_L1_Control::update_level_flight(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
Vector2f AP_L1_Control::_geo2planar(const Vector2f &ref, const Vector2f &wp)
|
Vector2f AP_L1_Control::_geo2planar(const Vector2f &ref, const Vector2f &wp) const
|
||||||
{
|
{
|
||||||
Vector2f out;
|
Vector2f out;
|
||||||
|
|
||||||
@ -327,17 +328,7 @@ float AP_L1_Control::_cross2D(const Vector2f &v1, const Vector2f &v2)
|
|||||||
return out;
|
return out;
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector2f AP_L1_Control::_planar2geo(const Vector2f &ref, const Vector2f &wp)
|
float AP_L1_Control::_maxf(const float &num1, const float &num2) const
|
||||||
{
|
|
||||||
Vector2f out;
|
|
||||||
|
|
||||||
out.x=degrees(wp.x)+ref.x;
|
|
||||||
out.y=degrees(wp.y*(1/cosf(radians(ref.x))))+ref.y;
|
|
||||||
|
|
||||||
return out;
|
|
||||||
}
|
|
||||||
|
|
||||||
float AP_L1_Control::_maxf(const float &num1, const float &num2)
|
|
||||||
{
|
{
|
||||||
float result;
|
float result;
|
||||||
|
|
||||||
|
@ -56,8 +56,6 @@ private:
|
|||||||
// reference to the AHRS object
|
// reference to the AHRS object
|
||||||
AP_AHRS *_ahrs;
|
AP_AHRS *_ahrs;
|
||||||
|
|
||||||
struct Location _current_loc;
|
|
||||||
|
|
||||||
// lateral acceration in m/s required to fly to the
|
// lateral acceration in m/s required to fly to the
|
||||||
// L1 reference point (+ve to right)
|
// L1 reference point (+ve to right)
|
||||||
float _latAccDem;
|
float _latAccDem;
|
||||||
@ -84,25 +82,16 @@ private:
|
|||||||
AP_Float _L1_period;
|
AP_Float _L1_period;
|
||||||
// L1 tracking loop damping ratio
|
// L1 tracking loop damping ratio
|
||||||
AP_Float _L1_damping;
|
AP_Float _L1_damping;
|
||||||
// L1 control loop enable
|
|
||||||
AP_Int8 _enable;
|
|
||||||
|
|
||||||
// Convert a 2D vector from latitude and longitude to planar
|
// Convert a 2D vector from latitude and longitude to planar
|
||||||
// coordinates based on a reference point
|
// coordinates based on a reference point
|
||||||
Vector2f _geo2planar(const Vector2f &ref, const Vector2f &wp);
|
Vector2f _geo2planar(const Vector2f &ref, const Vector2f &wp) const;
|
||||||
|
|
||||||
//Calculate the cross product of two 2D vectors
|
//Calculate the cross product of two 2D vectors
|
||||||
float _cross2D(const Vector2f &v1, const Vector2f &v2);
|
float _cross2D(const Vector2f &v1, const Vector2f &v2);
|
||||||
|
|
||||||
//Calculate the dot product of two 2D vectors
|
|
||||||
float _dot2D(const Vector2f &v1, const Vector2f &v2);
|
|
||||||
|
|
||||||
// Convert a 2D vector from planar coordinates to latitude and
|
|
||||||
// longitude based on a reference point
|
|
||||||
Vector2f _planar2geo(const Vector2f &ref, const Vector2f &wp);
|
|
||||||
|
|
||||||
//Calculate the maximum of two floating point numbers
|
//Calculate the maximum of two floating point numbers
|
||||||
float _maxf(const float &num1, const float &num2);
|
float _maxf(const float &num1, const float &num2) const;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user