Skip to content

Commit

Permalink
AC_AttitudeControl: make logging methods public/static so Blimp can u…
Browse files Browse the repository at this point in the history
…se them
  • Loading branch information
peterbarker committed Feb 28, 2024
1 parent fd807cd commit 9946951
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions libraries/AC_AttitudeControl/AC_PosControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -401,6 +401,10 @@ class AC_PosControl

static const struct AP_Param::GroupInfo var_info[];

static void Write_PSCN(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel);
static void Write_PSCE(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel);
static void Write_PSCD(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel);

protected:

// get throttle using vibration-resistant calculation (uses feed forward with manually calculated gain)
Expand Down Expand Up @@ -487,13 +491,9 @@ class AC_PosControl
// return true if on a real vehicle or SITL with lock-step scheduling
bool has_good_timing(void) const;

void Write_PSCN(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel);
void Write_PSCE(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel);
void Write_PSCD(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel);

private:
// convenience method for writing out the identical PSCE, PSCN, PSCD - and
// to save bytes
void Write_PSCx(LogMessages ID, float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel);
static void Write_PSCx(LogMessages ID, float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel);

};

0 comments on commit 9946951

Please sign in to comment.