Browse Source

VelocitySmoothing: simplify the API & fix style

sbg
Beat Küng 6 years ago committed by Roman Bapst
parent
commit
787d82c9e6
  1. 4
      src/lib/FlightTasks/tasks/ManualPositionSmoothVel/FlightTaskManualPositionSmoothVel.cpp
  2. 28
      src/lib/FlightTasks/tasks/Utility/VelocitySmoothing.cpp
  3. 42
      src/lib/FlightTasks/tasks/Utility/VelocitySmoothing.hpp

4
src/lib/FlightTasks/tasks/ManualPositionSmoothVel/FlightTaskManualPositionSmoothVel.cpp

@ -60,8 +60,6 @@ void FlightTaskManualPositionSmoothVel::_updateSetpoints()
_smoothing[1].setMaxAccel(MPC_ACC_HOR_MAX.get()); _smoothing[1].setMaxAccel(MPC_ACC_HOR_MAX.get());
_smoothing[0].setMaxVel(_constraints.speed_xy); _smoothing[0].setMaxVel(_constraints.speed_xy);
_smoothing[1].setMaxVel(_constraints.speed_xy); _smoothing[1].setMaxVel(_constraints.speed_xy);
_smoothing[0].setDt(_deltatime);
_smoothing[1].setDt(_deltatime);
Vector2f vel_xy = Vector2f(&_velocity(0)); Vector2f vel_xy = Vector2f(&_velocity(0));
float jerk = _jerk_max.get(); float jerk = _jerk_max.get();
@ -78,7 +76,7 @@ void FlightTaskManualPositionSmoothVel::_updateSetpoints()
for (int i = 0; i < 2; ++i) { for (int i = 0; i < 2; ++i) {
_smoothing[i].setMaxJerk(jerk); _smoothing[i].setMaxJerk(jerk);
_smoothing[i].updateDurations(_velocity_setpoint(i)); _smoothing[i].updateDurations(_deltatime, _velocity_setpoint(i));
} }
VelocitySmoothing::timeSynchronization(_smoothing, 2); VelocitySmoothing::timeSynchronization(_smoothing, 2);

28
src/lib/FlightTasks/tasks/Utility/VelocitySmoothing.cpp

@ -106,8 +106,10 @@ float VelocitySmoothing::computeT1(float T123, float accel_prev, float vel_prev,
float T13_minus = T1_minus + T3_minus; float T13_minus = T1_minus + T3_minus;
float T1 = 0.f; float T1 = 0.f;
if (T13_plus > T123) { if (T13_plus > T123) {
T1 = T1_minus; T1 = T1_minus;
} else if (T13_minus > T123) { } else if (T13_minus > T123) {
T1 = T1_plus; T1 = T1_plus;
} }
@ -161,18 +163,26 @@ void VelocitySmoothing::integrateT(float jerk, float accel_prev, float vel_prev,
pos_out = _dt / 3.f * (vel_out + accel_prev * _dt * 0.5f + 2.f * vel_prev) + _pos; pos_out = _dt / 3.f * (vel_out + accel_prev * _dt * 0.5f + 2.f * vel_prev) + _pos;
} }
void VelocitySmoothing::updateDurations(float vel_setpoint, float T123) void VelocitySmoothing::updateDurations(float dt, float vel_setpoint)
{
_vel_sp = vel_setpoint;
_dt = dt;
updateDurations();
}
void VelocitySmoothing::updateDurations(float T123)
{ {
float T1, T2, T3; float T1, T2, T3;
/* Depending of the direction, start accelerating positively or negatively */ /* Depending of the direction, start accelerating positively or negatively */
_max_jerk_T1 = (vel_setpoint - _vel > 0.f) ? _max_jerk : -_max_jerk; _max_jerk_T1 = (_vel_sp - _vel > 0.f) ? _max_jerk : -_max_jerk;
// compute increasing acceleration time // compute increasing acceleration time
if (PX4_ISFINITE(T123)) { if (PX4_ISFINITE(T123)) {
T1 = computeT1(T123, _accel, _vel, vel_setpoint, _max_jerk_T1); T1 = computeT1(T123, _accel, _vel, _vel_sp, _max_jerk_T1);
} else { } else {
T1 = computeT1(_accel, _vel, vel_setpoint, _max_jerk_T1); T1 = computeT1(_accel, _vel, _vel_sp, _max_jerk_T1);
} }
/* Force T1/2/3 to zero if smaller than an epoch to avoid chattering */ /* Force T1/2/3 to zero if smaller than an epoch to avoid chattering */
@ -190,8 +200,9 @@ void VelocitySmoothing::updateDurations(float vel_setpoint, float T123)
// compute constant acceleration time // compute constant acceleration time
if (PX4_ISFINITE(T123)) { if (PX4_ISFINITE(T123)) {
T2 = computeT2(T123, T1, T3); T2 = computeT2(T123, T1, T3);
} else { } else {
T2 = computeT2(T1, T3, _accel, _vel, vel_setpoint, _max_jerk_T1); T2 = computeT2(T1, T3, _accel, _vel, _vel_sp, _max_jerk_T1);
} }
if (T2 < _dt) { if (T2 < _dt) {
@ -201,7 +212,6 @@ void VelocitySmoothing::updateDurations(float vel_setpoint, float T123)
_T1 = T1; _T1 = T1;
_T2 = T2; _T2 = T2;
_T3 = T3; _T3 = T3;
_vel_sp = vel_setpoint;
} }
void VelocitySmoothing::integrate(float pos, float &vel_setpoint_smooth, void VelocitySmoothing::integrate(float pos, float &vel_setpoint_smooth,
@ -240,22 +250,24 @@ void VelocitySmoothing::integrate(float pos, float &vel_setpoint_smooth,
pos_setpoint_smooth = _pos; pos_setpoint_smooth = _pos;
} }
void VelocitySmoothing::timeSynchronization(VelocitySmoothing traj[3], int n_traj) void VelocitySmoothing::timeSynchronization(VelocitySmoothing *traj, int n_traj)
{ {
float desired_time = 0.f; float desired_time = 0.f;
int longest_traj_index = 0; int longest_traj_index = 0;
for (int i = 0; i < n_traj; i++) { for (int i = 0; i < n_traj; i++) {
const float T123 = traj[i].getTotalTime(); const float T123 = traj[i].getTotalTime();
if (T123 > desired_time) { if (T123 > desired_time) {
desired_time = T123; desired_time = T123;
longest_traj_index = i; longest_traj_index = i;
} }
} }
if (desired_time > FLT_EPSILON) { if (desired_time > FLT_EPSILON) {
for (int i = 0; i < n_traj; i++) { for (int i = 0; i < n_traj; i++) {
if (i != longest_traj_index) { if (i != longest_traj_index) {
traj[i].updateDurations(traj[i].getVelSp(), desired_time); traj[i].updateDurations(desired_time);
} }
} }
} }

42
src/lib/FlightTasks/tasks/Utility/VelocitySmoothing.hpp

@ -68,12 +68,12 @@ public:
void reset(float accel, float vel, float pos); void reset(float accel, float vel, float pos);
/** /**
* Compute T1, T2, T3 depending on the current state and velocity setpoint. This should be called on every cycle. * Compute T1, T2, T3 depending on the current state and velocity setpoint. This should be called on every cycle
* and before integrate().
* @param dt delta time between last updateDurations() call and now [s]
* @param vel_setpoint velocity setpoint input * @param vel_setpoint velocity setpoint input
* @param T123 optional parameter. If set, the total trajectory time will be T123, if not,
* the algorithm optimizes for time.
*/ */
void updateDurations(float vel_setpoint, float T123 = NAN); void updateDurations(float dt, float vel_setpoint);
/** /**
* Generate the trajectory (acceleration, velocity and position) by integrating the current jerk * Generate the trajectory (acceleration, velocity and position) by integrating the current jerk
@ -93,22 +93,25 @@ public:
float getMaxVel() const { return _max_vel; } float getMaxVel() const { return _max_vel; }
void setMaxVel(float max_vel) { _max_vel = max_vel; } void setMaxVel(float max_vel) { _max_vel = max_vel; }
/* Other getters and setters */
float getTotalTime() const {return _T1 + _T2 + _T3; }
float getVelSp() const {return _vel_sp; }
void setDt(float dt) {_dt = dt; } // delta time between last update() call and now [s]
/** /**
* Synchronize several trajectories to have the same total time. This is required to generate * Synchronize several trajectories to have the same total time. This is required to generate
* straight lines. * straight lines.
* The resulting total time is the one of the longest trajectory. * The resulting total time is the one of the longest trajectory.
* @param traj[3] a table of VelocitySmoothing objects * @param traj an array of VelocitySmoothing objects
* n_traj the number of trajectories to be synchronized * @param n_traj the number of trajectories to be synchronized
*/ */
static void timeSynchronization(VelocitySmoothing traj[3], int n_traj); static void timeSynchronization(VelocitySmoothing *traj, int n_traj);
private: private:
float getTotalTime() const { return _T1 + _T2 + _T3; }
float getVelSp() const { return _vel_sp; }
/**
* Compute T1, T2, T3 depending on the current state and velocity setpoint.
* @param T123 optional parameter. If set, the total trajectory time will be T123, if not,
* the algorithm optimizes for time.
*/
void updateDurations(float T123 = NAN);
/** /**
* Compute increasing acceleration time * Compute increasing acceleration time
*/ */
@ -136,6 +139,10 @@ private:
inline void integrateT(float jerk, float accel_prev, float vel_prev, float pos_prev, inline void integrateT(float jerk, float accel_prev, float vel_prev, float pos_prev,
float &accel_out, float &vel_out, float &pos_out); float &accel_out, float &vel_out, float &pos_out);
/* Inputs */
float _vel_sp;
float _dt = 0.f;
/* Constraints */ /* Constraints */
float _max_jerk = 22.f; float _max_jerk = 22.f;
float _max_accel = 8.f; float _max_accel = 8.f;
@ -150,12 +157,9 @@ private:
float _max_jerk_T1 = 0.f; ///< jerk during phase T1 (with correct sign) float _max_jerk_T1 = 0.f; ///< jerk during phase T1 (with correct sign)
/* Duration of each phase */ /* Duration of each phase */
float _T1 = 0.f; // Increasing acceleration float _T1 = 0.f; ///< Increasing acceleration [s]
float _T2 = 0.f; // Constant acceleration float _T2 = 0.f; ///< Constant acceleration [s]
float _T3 = 0.f; // Decreasing acceleration float _T3 = 0.f; ///< Decreasing acceleration [s]
float _vel_sp;
float _dt = 0.f;
static constexpr float max_pos_err = 1.f; ///< maximum position error (if above, the position setpoint is locked) static constexpr float max_pos_err = 1.f; ///< maximum position error (if above, the position setpoint is locked)
}; };

Loading…
Cancel
Save