AC_PosControl: accessors to log z-axis vel and accel

This commit is contained in:
Leonard Hall 2015-04-05 16:53:11 +09:30 committed by Randy Mackay
parent b50f065cab
commit a632a57d79
2 changed files with 5 additions and 3 deletions

View File

@ -311,7 +311,6 @@ void AC_PosControl::rate_to_accel_z()
{
const Vector3f& curr_vel = _inav.get_velocity();
float p; // used to capture pid values for logging
float desired_accel; // the target acceleration if the accel based throttle is enabled, otherwise the output to be sent to the motors
// check speed limits
// To-Do: check these speed limits here or in the pos->rate controller
@ -361,10 +360,10 @@ void AC_PosControl::rate_to_accel_z()
p = _p_vel_z.kP() * _vel_error.z;
// consolidate and constrain target acceleration
desired_accel = _accel_feedforward.z + p;
_accel_target.z = _accel_feedforward.z + p;
// set target for accel based throttle controller
accel_to_throttle(desired_accel);
accel_to_throttle(_accel_target.z);
}
// accel_to_throttle - alt hold's acceleration controller

View File

@ -93,6 +93,9 @@ public:
/// get_speed_down - accessors for current down speed in cm/s. Will be a negative number
float get_speed_down() const { return _speed_down_cms; }
/// get_vel_target_z - returns current vertical speed in cm/s
float get_vel_target_z() const { return _vel_target.z; }
/// set_accel_z - set vertical acceleration in cm/s/s
/// leash length will be recalculated the next time update_z_controller() is called
void set_accel_z(float accel_cmss);