mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AC_AttitudeControl: added get_rpy_PDmod method
used for lua scripts to do VTOL tuning
This commit is contained in:
parent
9cf065072b
commit
f8fe74f5fe
@ -11,6 +11,8 @@ extern const AP_HAL::HAL& hal;
|
|||||||
# define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.15f // Medium
|
# define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.15f // Medium
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
AC_AttitudeControl *AC_AttitudeControl::_singleton;
|
||||||
|
|
||||||
// table of user settable parameters
|
// table of user settable parameters
|
||||||
const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
|
const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
|
||||||
|
|
||||||
@ -1129,3 +1131,14 @@ bool AC_AttitudeControl::pre_arm_checks(const char *param_prefix,
|
|||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
get the PDmod value for roll, pitch and yaw, for oscillation
|
||||||
|
detection in lua scripts
|
||||||
|
*/
|
||||||
|
void AC_AttitudeControl::get_rpy_PDmod(float &roll_dmod, float &pitch_dmod, float &yaw_dmod)
|
||||||
|
{
|
||||||
|
roll_dmod = get_rate_roll_pid().get_pid_info().Dmod;
|
||||||
|
pitch_dmod = get_rate_pitch_pid().get_pid_info().Dmod;
|
||||||
|
yaw_dmod = get_rate_yaw_pid().get_pid_info().Dmod;
|
||||||
|
}
|
||||||
|
@ -64,9 +64,14 @@ public:
|
|||||||
_aparm(aparm),
|
_aparm(aparm),
|
||||||
_motors(motors)
|
_motors(motors)
|
||||||
{
|
{
|
||||||
|
_singleton = this;
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static AC_AttitudeControl *get_singleton(void) {
|
||||||
|
return _singleton;
|
||||||
|
}
|
||||||
|
|
||||||
// Empty destructor to suppress compiler warning
|
// Empty destructor to suppress compiler warning
|
||||||
virtual ~AC_AttitudeControl() {}
|
virtual ~AC_AttitudeControl() {}
|
||||||
|
|
||||||
@ -363,6 +368,9 @@ public:
|
|||||||
// enable inverted flight on backends that support it
|
// enable inverted flight on backends that support it
|
||||||
virtual void set_inverted_flight(bool inverted) {}
|
virtual void set_inverted_flight(bool inverted) {}
|
||||||
|
|
||||||
|
// get the PDmod value for roll, pitch and yaw, for oscillation detection in lua scripts
|
||||||
|
void get_rpy_PDmod(float &roll_dmod, float &pitch_dmod, float &yaw_dmod);
|
||||||
|
|
||||||
// User settable parameters
|
// User settable parameters
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
@ -483,6 +491,8 @@ protected:
|
|||||||
const AP_Vehicle::MultiCopter &_aparm;
|
const AP_Vehicle::MultiCopter &_aparm;
|
||||||
AP_Motors& _motors;
|
AP_Motors& _motors;
|
||||||
|
|
||||||
|
static AC_AttitudeControl *_singleton;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
/*
|
/*
|
||||||
state of control monitoring
|
state of control monitoring
|
||||||
|
Loading…
Reference in New Issue
Block a user