ardupilot/libraries/AC_AttitudeControl/AC_CommandModel.h

38 lines
882 B
C
Raw Normal View History

#pragma once
/// @file AC_CommandModel.h
/// @brief ArduCopter Command Model Library
#include <AP_Param/AP_Param.h>
/*
Command model parameters
*/
class AC_CommandModel {
public:
AC_CommandModel(float initial_rate, float initial_expo, float initial_tc);
2022-05-21 23:50:38 -03:00
// Accessors for parameters
float get_rate_tc() const { return rate_tc; }
float get_rate() const { return rate; }
float get_expo() const { return expo; }
2022-05-21 23:50:38 -03:00
// Set the max rate
void set_rate(float input) { rate.set(input); }
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];
protected:
2022-05-21 23:50:38 -03:00
AP_Float rate_tc; // rate time constant
AP_Float rate; // maximum rate
AP_Float expo; // expo shaping
private:
const float default_rate_tc;
const float default_rate;
const float default_expo;
};