From 171203370f8b21ce78963d3e406d045c1b01e613 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 24 Jan 2014 15:46:45 +0900 Subject: [PATCH] AC_PosControl: add accessor for speed_up and down --- libraries/AC_AttitudeControl/AC_PosControl.h | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index 3cef902022..8cd9d2ba67 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -65,8 +65,15 @@ public: /// set_speed_z - sets maximum climb and descent rates /// To-Do: call this in the main code as part of flight mode initialisation /// calc_leash_length_z should be called afterwards + /// speed_down should be a negative number void set_speed_z(float speed_down, float speed_up); + /// get_speed_up - accessor for current up speed in cm/s + float get_speed_up() { return _speed_up_cms; } + + /// get_speed_down - accessors for current down speed in cm/s. Will be a negative number + float get_speed_down() { return _speed_down_cms; } + /// set_accel_z - set vertical acceleration in cm/s/s /// calc_leash_length_z should be called afterwards void set_accel_z(float accel_cmss);