mirror of https://github.com/ArduPilot/ardupilot
AC_AttitudeControl: add command model class for parameters
This commit is contained in:
parent
a547916ebf
commit
1cd537895e
|
@ -0,0 +1,37 @@
|
|||
#include "AC_CommandModel.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// table of user settable parameters
|
||||
const AP_Param::GroupInfo AC_CommandModel::var_info[] = {
|
||||
|
||||
// @Param: RATE
|
||||
// @DisplayName: Maximum Controlled Rate
|
||||
// @Description: Sets the maximum rate commanded.
|
||||
// @Units: deg/s
|
||||
// @Range: 1 360
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RATE", 1, AC_CommandModel, rate, 202.5),
|
||||
|
||||
// @Param: EXPO
|
||||
// @DisplayName: Controlled Expo
|
||||
// @Description: Controlled expo to allow faster rotation when stick at edges
|
||||
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
|
||||
// @Range: -0.5 1.0
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("EXPO", 2, AC_CommandModel, expo, 0),
|
||||
|
||||
// @Param: RATE_TC
|
||||
// @DisplayName: Rate control input time constant
|
||||
// @Description: Rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response
|
||||
// @Units: s
|
||||
// @Range: 0 1
|
||||
// @Increment: 0.01
|
||||
// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RATE_TC", 3, AC_CommandModel, rate_tc, 0.05f),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
@ -0,0 +1,34 @@
|
|||
#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(void)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
float get_rate_tc() { return rate_tc; }
|
||||
float get_rate() { return rate; }
|
||||
float get_expo() { return expo; }
|
||||
|
||||
void set_rate(float input) { rate = input; }
|
||||
|
||||
// var_info for holding Parameter information
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
protected:
|
||||
AP_Float rate_tc;
|
||||
AP_Float rate;
|
||||
AP_Float expo;
|
||||
|
||||
};
|
||||
|
Loading…
Reference in New Issue