Path: blob/master/libraries/AC_AttitudeControl/AC_CommandModel.h
9444 views
#pragma once12/// @file AC_CommandModel.h3/// @brief ArduCopter Command Model Library45#include <AP_Param/AP_Param.h>67/*8Command model parameters9*/1011class AC_CommandModel {12public:13AC_CommandModel(float initial_rate, float initial_expo, float initial_tc);1415// Accessors for parameters16float get_rate_tc() const { return rate_tc; }17float get_rate() const { return rate; }18float get_expo() const { return expo; }1920// Set the max rate21void set_rate(float input) { rate.set(input); }2223// var_info for holding Parameter information24static const struct AP_Param::GroupInfo var_info[];2526protected:27AP_Float rate_tc; // rate time constant28AP_Float rate; // maximum rate29AP_Float expo; // expo shaping3031private:32const float default_rate_tc;33const float default_rate;34const float default_expo;35};36373839