mirror of https://github.com/ArduPilot/ardupilot
AP_Math: cleanup position control APIs
use Vector2 for xy, float for z
This commit is contained in:
parent
fe4abc521a
commit
86f09cad09
|
@ -37,13 +37,6 @@ void update_vel_accel(float& vel, float accel, float dt, float limit)
|
|||
}
|
||||
}
|
||||
|
||||
// update_vel_accel_z - single axis projection of position and velocity, pos and vel, forwards in time based on a time step of dt and acceleration of accel.
|
||||
// the velocity is not moved in the direction of limit if limit is not set to zero
|
||||
void update_vel_accel_z(Vector3f& vel, const Vector3f& accel, float dt, Vector3f limit)
|
||||
{
|
||||
update_vel_accel(vel.z, accel.z, dt, limit.z);
|
||||
}
|
||||
|
||||
// update_pos_vel_accel - single axis projection of position and velocity, pos and vel, forwards in time based on a time step of dt and acceleration of accel.
|
||||
// the position and velocity is not moved in the direction of limit if limit is not set to zero
|
||||
void update_pos_vel_accel(float& pos, float& vel, float accel, float dt, float limit)
|
||||
|
@ -57,16 +50,9 @@ void update_pos_vel_accel(float& pos, float& vel, float accel, float dt, float l
|
|||
update_vel_accel(vel, accel, dt, limit);
|
||||
}
|
||||
|
||||
// update_pos_vel_accel_z - single axis projection of position and velocity, pos and vel, forwards in time based on a time step of dt and acceleration of accel.
|
||||
// the position and velocity is not moved in the direction of limit if limit is not set to zero
|
||||
void update_pos_vel_accel_z(Vector3f& pos, Vector3f& vel, const Vector3f& accel, float dt, Vector3f limit)
|
||||
{
|
||||
update_pos_vel_accel(pos.z, vel.z, accel.z, dt, limit.z);
|
||||
}
|
||||
|
||||
// update_vel_accel - dual axis projection of position and velocity, pos and vel, forwards in time based on a time step of dt and acceleration of accel.
|
||||
// the velocity is not moved in the direction of limit if limit is not set to zero
|
||||
void update_vel_accel(Vector2f& vel, const Vector2f& accel, float dt, Vector2f limit)
|
||||
void update_vel_accel_xy(Vector2f& vel, const Vector2f& accel, float dt, Vector2f limit)
|
||||
{
|
||||
// increase velocity by acceleration * dt if it does not increase error when limited.
|
||||
Vector2f delta_vel = accel * dt;
|
||||
|
@ -80,22 +66,9 @@ void update_vel_accel(Vector2f& vel, const Vector2f& accel, float dt, Vector2f l
|
|||
vel += delta_vel;
|
||||
}
|
||||
|
||||
// update_vel_accel_xy - dual axis projection of position and velocity, pos and vel, forwards in time based on a time step of dt and acceleration of accel.
|
||||
// the velocity is not moved in the direction of limit if limit is not set to zero
|
||||
// This function only updates the x and y axis leaving the z axis unchanged.
|
||||
void update_vel_accel_xy(Vector3f& vel, const Vector3f& accel, float dt, Vector3f limit)
|
||||
{
|
||||
Vector2f vel_2f {vel.x, vel.y};
|
||||
const Vector2f accel_2f {accel.x, accel.y};
|
||||
const Vector2f limit_2f {limit.x, limit.y};
|
||||
update_vel_accel(vel_2f, accel_2f, dt, limit_2f);
|
||||
vel.x = vel_2f.x;
|
||||
vel.y = vel_2f.y;
|
||||
}
|
||||
|
||||
// update_pos_vel_accel - dual axis projection of position and velocity, pos and vel, forwards in time based on a time step of dt and acceleration of accel.
|
||||
// the position and velocity is not moved in the direction of limit if limit is not set to zero
|
||||
void update_pos_vel_accel(Vector2f& pos, Vector2f& vel, const Vector2f& accel, float dt, Vector2f limit)
|
||||
void update_pos_vel_accel_xy(Vector2f& pos, Vector2f& vel, const Vector2f& accel, float dt, Vector2f limit)
|
||||
{
|
||||
// move position and velocity forward by dt.
|
||||
Vector2f delta_pos = vel * dt + accel * 0.5f * sq(dt);
|
||||
|
@ -110,23 +83,7 @@ void update_pos_vel_accel(Vector2f& pos, Vector2f& vel, const Vector2f& accel, f
|
|||
|
||||
pos += delta_pos;
|
||||
|
||||
update_vel_accel(vel, accel, dt, limit);
|
||||
}
|
||||
|
||||
// update_pos_vel_accel_xy - dual axis projection of position and velocity, pos and vel, forwards in time based on a time step of dt and acceleration of accel.
|
||||
// the position and velocity is not moved in the direction of limit if limit is not set to zero
|
||||
// This function only updates the x and y axis leaving the z axis unchanged.
|
||||
void update_pos_vel_accel_xy(Vector3f& pos, Vector3f& vel, const Vector3f& accel, float dt, Vector3f limit)
|
||||
{
|
||||
Vector2f pos_2f {pos.x, pos.y};
|
||||
Vector2f vel_2f {vel.x, vel.y};
|
||||
const Vector2f accel_2f {accel.x, accel.y};
|
||||
const Vector2f limit_2f {limit.x, limit.y};
|
||||
update_pos_vel_accel(pos_2f, vel_2f, accel_2f, dt, limit_2f);
|
||||
pos.x = pos_2f.x;
|
||||
pos.y = pos_2f.y;
|
||||
vel.x = vel_2f.x;
|
||||
vel.y = vel_2f.y;
|
||||
update_vel_accel_xy(vel, accel, dt, limit);
|
||||
}
|
||||
|
||||
/* shape_accel calculates a jerk limited path from the current acceleration to an input acceleration.
|
||||
|
@ -223,11 +180,11 @@ void shape_accel_xy(const Vector2f& accel_input, Vector2f& accel,
|
|||
The function alters the input velocity to be the velocity that the system could reach zero acceleration in the minimum time.
|
||||
The accel_max limit can be removed by setting it to zero.
|
||||
*/
|
||||
void shape_vel_accel(float vel_input, float accel_input,
|
||||
float vel, float& accel,
|
||||
float vel_min, float vel_max,
|
||||
float accel_min, float accel_max,
|
||||
float tc, float dt)
|
||||
void shape_vel_accel(float &vel_input, float accel_input,
|
||||
float vel, float& accel,
|
||||
float vel_min, float vel_max,
|
||||
float accel_min, float accel_max,
|
||||
float tc, float dt)
|
||||
{
|
||||
// sanity check tc
|
||||
if (!is_positive(tc)) {
|
||||
|
@ -254,19 +211,6 @@ void shape_vel_accel(float vel_input, float accel_input,
|
|||
shape_accel(accel_target, accel, accel_min, accel_max, tc, dt);
|
||||
}
|
||||
|
||||
void shape_vel_accel_z(const Vector3f& vel_input, const Vector3f& accel_input,
|
||||
const Vector3f& vel, Vector3f& accel,
|
||||
float vel_min, float vel_max,
|
||||
float accel_min, float accel_max,
|
||||
float tc, float dt)
|
||||
{
|
||||
shape_vel_accel(vel_input.z, accel_input.z,
|
||||
vel.z, accel.z,
|
||||
vel_min, vel_max,
|
||||
accel_min, accel_max,
|
||||
tc, dt);
|
||||
}
|
||||
|
||||
/* shape_vel_accel_xy calculate a jerk limited path from the current position, velocity and acceleration to an input velocity.
|
||||
The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
|
||||
The kinematic path is constrained by:
|
||||
|
@ -280,8 +224,8 @@ void shape_vel_accel_z(const Vector3f& vel_input, const Vector3f& accel_input,
|
|||
This function operates on the x and y axis of both Vector2f or Vector3f inputs.
|
||||
The accel_max limit can be removed by setting it to zero.
|
||||
*/
|
||||
void shape_vel_accel_xy(Vector2f vel_input, const Vector2f& accel_input,
|
||||
const Vector2f& vel, Vector2f& accel, float vel_max, float accel_max, float tc, float dt)
|
||||
void shape_vel_accel_xy(Vector2f &vel_input, const Vector2f& accel_input,
|
||||
const Vector2f& vel, Vector2f& accel, float vel_max, float accel_max, float tc, float dt)
|
||||
{
|
||||
// sanity check tc
|
||||
if (!is_positive(tc)) {
|
||||
|
@ -308,19 +252,6 @@ void shape_vel_accel_xy(Vector2f vel_input, const Vector2f& accel_input,
|
|||
shape_accel_xy(accel_target, accel, accel_max, tc, dt);
|
||||
}
|
||||
|
||||
void shape_vel_accel_xy(const Vector3f& vel_input, const Vector3f& accel_input,
|
||||
const Vector3f& vel, Vector3f& accel, float vel_max, float accel_max, float tc, float dt)
|
||||
{
|
||||
Vector2f vel_input_2f {vel_input.x, vel_input.y};
|
||||
const Vector2f accel_input_2f {accel_input.x, accel_input.y};
|
||||
const Vector2f vel_2f {vel.x, vel.y};
|
||||
Vector2f accel_2f {accel.x, accel.y};
|
||||
|
||||
shape_vel_accel_xy(vel_input_2f, accel_input_2f, vel_2f, accel_2f, vel_max, accel_max, tc, dt);
|
||||
accel.x = accel_2f.x;
|
||||
accel.y = accel_2f.y;
|
||||
}
|
||||
|
||||
/* shape_pos_vel_accel calculate a jerk limited path from the current position, velocity and acceleration to an input position and velocity.
|
||||
The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
|
||||
The kinematic path is constrained by :
|
||||
|
@ -333,10 +264,10 @@ void shape_vel_accel_xy(const Vector3f& vel_input, const Vector3f& accel_input,
|
|||
The function alters the input position to be the closest position that the system could reach zero acceleration in the minimum time.
|
||||
The vel_max, vel_correction_max, and accel_max limits can be removed by setting the desired limit to zero.
|
||||
*/
|
||||
void shape_pos_vel_accel(float pos_input, float vel_input, float accel_input,
|
||||
float pos, float vel, float& accel,
|
||||
float vel_correction_max, float vel_min, float vel_max,
|
||||
float accel_min, float accel_max, float tc, float dt)
|
||||
void shape_pos_vel_accel(float &pos_input, float vel_input, float accel_input,
|
||||
float pos, float vel, float& accel,
|
||||
float vel_correction_max, float vel_min, float vel_max,
|
||||
float accel_min, float accel_max, float tc, float dt)
|
||||
{
|
||||
// sanity check tc
|
||||
if (!is_positive(tc)) {
|
||||
|
@ -364,18 +295,6 @@ void shape_pos_vel_accel(float pos_input, float vel_input, float accel_input,
|
|||
shape_vel_accel(vel_target, accel_input, vel, accel, vel_min, vel_max, accel_min, accel_max, tc, dt);
|
||||
}
|
||||
|
||||
void shape_pos_vel_accel_z(const Vector3f& pos_input, const Vector3f& vel_input, const Vector3f& accel_input,
|
||||
const Vector3f& pos, const Vector3f& vel, Vector3f& accel,
|
||||
float vel_correction_max, float vel_min, float vel_max,
|
||||
float accel_min, float accel_max, float tc, float dt)
|
||||
{
|
||||
shape_pos_vel_accel(pos_input.z, vel_input.z, accel_input.z,
|
||||
pos.z, vel.z, accel.z,
|
||||
vel_correction_max, vel_min, vel_max,
|
||||
accel_min, accel_max,
|
||||
tc, dt);
|
||||
}
|
||||
|
||||
/* shape_pos_vel_accel_xy calculate a jerk limited path from the current position, velocity and acceleration to an input position and velocity.
|
||||
The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
|
||||
The kinematic path is constrained by:
|
||||
|
@ -418,36 +337,6 @@ void shape_pos_vel_accel_xy(const Vector2f& pos_input, const Vector2f& vel_input
|
|||
shape_vel_accel_xy(vel_target, accel_input, vel, accel, vel_max, accel_max, tc, dt);
|
||||
}
|
||||
|
||||
/* shape_pos_vel_accel_xy calculate a jerk limited path from the current position, velocity and acceleration to an input position and velocity.
|
||||
The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
|
||||
The kinematic path is constrained by:
|
||||
vel_max : maximum velocity
|
||||
accel_max : maximum acceleration
|
||||
tc : time constant
|
||||
The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration.
|
||||
The time constant also defines the time taken to achieve the maximum acceleration.
|
||||
The time constant must be positive.
|
||||
The function alters the input position to be the closest position that the system could reach zero acceleration in the minimum time.
|
||||
This function operates only on the x and y axis of the Vector2f or Vector3f inputs.
|
||||
The vel_max, vel_correction_max, and accel_max limits can be removed by setting the desired limit to zero.
|
||||
*/
|
||||
void shape_pos_vel_accel_xy(const Vector3f& pos_input, const Vector3f& vel_input, const Vector3f& accel_input,
|
||||
const Vector3f& pos, const Vector3f& vel, Vector3f& accel,
|
||||
float vel_max, float vel_correction_max, float accel_max, float tc, float dt)
|
||||
{
|
||||
const Vector2f pos_input_2f {pos_input.x, pos_input.y};
|
||||
const Vector2f vel_input_2f {vel_input.x, vel_input.y};
|
||||
const Vector2f accel_input_2f {accel_input.x, accel_input.y};
|
||||
const Vector2f pos_2f {pos.x, pos.y};
|
||||
const Vector2f vel_2f {vel.x, vel.y};
|
||||
Vector2f accel_2f {accel.x, accel.y};
|
||||
|
||||
shape_pos_vel_accel_xy(pos_input_2f, vel_input_2f, accel_input_2f,
|
||||
pos_2f, vel_2f, accel_2f, vel_max, vel_correction_max, accel_max, tc, dt);
|
||||
accel.x = accel_2f.x;
|
||||
accel.y = accel_2f.y;
|
||||
}
|
||||
|
||||
// proportional controller with piecewise sqrt sections to constrain second derivative
|
||||
float sqrt_controller(float error, float p, float second_ord_lim, float dt)
|
||||
{
|
||||
|
|
|
@ -7,20 +7,16 @@
|
|||
// update_vel_accel projects the velocity, vel, forward in time based on a time step of dt and acceleration of accel.
|
||||
// update_vel_accel - single axis projection.
|
||||
void update_vel_accel(float& vel, float accel, float dt, float limit);
|
||||
void update_vel_accel_z(Vector3f& vel, const Vector3f& accel, float dt, Vector3f limit);
|
||||
|
||||
// update_vel_accel projects the velocity, vel, forward in time based on a time step of dt and acceleration of accel.
|
||||
// update_vel_accel - single axis projection.
|
||||
void update_pos_vel_accel(float& pos, float& vel, float accel, float dt, float limit);
|
||||
void update_pos_vel_accel_z(Vector3f& pos, Vector3f& vel, const Vector3f& accel, float dt, Vector3f limit);
|
||||
|
||||
// update_pos_vel_accel_xy - dual axis projection operating on the x, y axis of Vector2f or Vector3f inputs.
|
||||
void update_vel_accel(Vector2f& vel, const Vector2f& accel, float dt, Vector2f limit);
|
||||
void update_vel_accel_xy(Vector3f& vel, const Vector3f& accel, float dt, Vector3f limit);
|
||||
void update_vel_accel_xy(Vector2f& vel, const Vector2f& accel, float dt, Vector2f limit);
|
||||
|
||||
// update_pos_vel_accel_xy - dual axis projection operating on the x, y axis of Vector2f or Vector3f inputs.
|
||||
void update_pos_vel_accel(Vector2f& pos, Vector2f& vel, const Vector2f& accel, float dt, Vector2f limit);
|
||||
void update_pos_vel_accel_xy(Vector3f& pos, Vector3f& vel, const Vector3f& accel, float dt, Vector3f limit);
|
||||
void update_pos_vel_accel_xy(Vector2f& pos, Vector2f& vel, const Vector2f& accel, float dt, Vector2f limit);
|
||||
|
||||
/* shape_accel calculates a jerk limited path from the current acceleration to an input acceleration.
|
||||
The function takes the current acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
|
||||
|
@ -33,11 +29,11 @@ void update_pos_vel_accel_xy(Vector3f& pos, Vector3f& vel, const Vector3f& accel
|
|||
The function alters the input velocity to be the velocity that the system could reach zero acceleration in the minimum time.
|
||||
*/
|
||||
void shape_accel(float accel_input, float& accel,
|
||||
float accel_min, float accel_max,
|
||||
float tc, float dt);
|
||||
float accel_min, float accel_max,
|
||||
float tc, float dt);
|
||||
|
||||
void shape_accel_xy(const Vector2f& accel_input, Vector2f& accel,
|
||||
float accel_max, float tc, float dt);
|
||||
float accel_max, float tc, float dt);
|
||||
|
||||
/* shape_vel calculates a jerk limited path from the current velocity and acceleration to an input velocity.
|
||||
The function takes the current velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
|
||||
|
@ -50,17 +46,11 @@ void shape_accel_xy(const Vector2f& accel_input, Vector2f& accel,
|
|||
The time constant must be positive.
|
||||
The function alters the input velocity to be the velocity that the system could reach zero acceleration in the minimum time.
|
||||
*/
|
||||
void shape_vel_accel(float vel_input, float accel_input,
|
||||
float vel, float& accel,
|
||||
float vel_min, float vel_max,
|
||||
float accel_min, float accel_max,
|
||||
float tc, float dt);
|
||||
|
||||
void shape_vel_accel_z(const Vector3f& vel_input, const Vector3f& accel_input,
|
||||
const Vector3f& vel, Vector3f& accel,
|
||||
float vel_min, float vel_max,
|
||||
float accel_min, float accel_max,
|
||||
float tc, float dt);
|
||||
void shape_vel_accel(float &vel_input, const float accel_input,
|
||||
float vel, float& accel,
|
||||
float vel_min, float vel_max,
|
||||
float accel_min, float accel_max,
|
||||
float tc, float dt);
|
||||
|
||||
/* shape_vel_xy calculate a jerk limited path from the current position, velocity and acceleration to an input velocity.
|
||||
The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
|
||||
|
@ -75,11 +65,8 @@ void shape_vel_accel_z(const Vector3f& vel_input, const Vector3f& accel_input,
|
|||
This function operates on the x and y axis of both Vector2f or Vector3f inputs.
|
||||
The accel_max limit can be removed by setting it to zero.
|
||||
*/
|
||||
void shape_vel_accel_xy(Vector2f vel_input, const Vector2f& accel_input,
|
||||
const Vector2f& vel, Vector2f& accel, float vel_max, float accel_max, float tc, float dt);
|
||||
|
||||
void shape_vel_accel_xy(const Vector3f& vel_input, const Vector3f& accel_input,
|
||||
const Vector3f& vel, Vector3f& accel, float vel_max, float accel_max, float tc, float dt);
|
||||
void shape_vel_accel_xy(Vector2f &vel_input, const Vector2f& accel_input,
|
||||
const Vector2f& vel, Vector2f& accel, float vel_max, float accel_max, float tc, float dt);
|
||||
|
||||
/* shape_pos_vel calculate a jerk limited path from the current position, velocity and acceleration to an input position and velocity.
|
||||
The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
|
||||
|
@ -92,15 +79,10 @@ void shape_vel_accel_xy(const Vector3f& vel_input, const Vector3f& accel_input,
|
|||
The time constant must be positive.
|
||||
The function alters the input position to be the closest position that the system could reach zero acceleration in the minimum time.
|
||||
*/
|
||||
void shape_pos_vel_accel(float pos_input, float vel_input, float accel_input,
|
||||
float pos, float vel, float& accel,
|
||||
float vel_correction_max, float vel_min, float vel_max,
|
||||
float accel_min, float accel_max, float tc, float dt);
|
||||
|
||||
void shape_pos_vel_accel_z(const Vector3f& pos_input, const Vector3f& vel_input, const Vector3f& accel_input,
|
||||
const Vector3f& pos, const Vector3f& vel, Vector3f& accel,
|
||||
float vel_correction_max, float vel_min, float vel_max,
|
||||
float accel_min, float accel_max, float tc, float dt);
|
||||
void shape_pos_vel_accel(float &pos_input, const float vel_input, const float accel_input,
|
||||
float pos, float vel, float& accel,
|
||||
float vel_correction_max, float vel_min, float vel_max,
|
||||
float accel_min, float accel_max, float tc, float dt);
|
||||
|
||||
/* shape_pos_vel_xy calculate a jerk limited path from the current position, velocity and acceleration to an input position and velocity.
|
||||
The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
|
||||
|
@ -119,10 +101,6 @@ void shape_pos_vel_accel_xy(const Vector2f& pos_input, const Vector2f& vel_input
|
|||
const Vector2f& pos, const Vector2f& vel, Vector2f& accel,
|
||||
float vel_correction_max, float vel_max, float accel_max, float tc, float dt);
|
||||
|
||||
void shape_pos_vel_accel_xy(const Vector3f& pos_input, const Vector3f& vel_input, const Vector3f& accel_input,
|
||||
const Vector3f& pos, const Vector3f& vel, Vector3f& accel,
|
||||
float vel_max, float vel_correction_max, float accel_max, float tc, float dt);
|
||||
|
||||
// proportional controller with piecewise sqrt sections to constrain second derivative
|
||||
float sqrt_controller(float error, float p, float second_ord_lim, float dt);
|
||||
|
||||
|
|
Loading…
Reference in New Issue