mirror of https://github.com/ArduPilot/ardupilot
Copter: add roll-pitch slew for auto modes
Added reporting of roll, pitch inputs for ACRO, AUTO
This commit is contained in:
parent
e297ba7d18
commit
d6ff5ae261
|
@ -1609,6 +1609,9 @@ void update_roll_pitch_mode(void)
|
||||||
{
|
{
|
||||||
switch(roll_pitch_mode) {
|
switch(roll_pitch_mode) {
|
||||||
case ROLL_PITCH_ACRO:
|
case ROLL_PITCH_ACRO:
|
||||||
|
// copy user input for reporting purposes
|
||||||
|
control_roll = g.rc_1.control_in;
|
||||||
|
control_pitch = g.rc_2.control_in;
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
if(g.axis_enabled) {
|
if(g.axis_enabled) {
|
||||||
|
@ -1651,9 +1654,13 @@ void update_roll_pitch_mode(void)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ROLL_PITCH_AUTO:
|
case ROLL_PITCH_AUTO:
|
||||||
|
// copy user input for reporting purposes
|
||||||
|
control_roll = g.rc_1.control_in;
|
||||||
|
control_pitch = g.rc_2.control_in;
|
||||||
|
|
||||||
// copy latest output from nav controller to stabilize controller
|
// copy latest output from nav controller to stabilize controller
|
||||||
nav_roll = auto_roll;
|
nav_roll += constrain_int32(wrap_180(auto_roll - nav_roll), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second
|
||||||
nav_pitch = auto_pitch;
|
nav_pitch += constrain_int32(wrap_180(auto_pitch - nav_pitch), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second
|
||||||
get_stabilize_roll(nav_roll);
|
get_stabilize_roll(nav_roll);
|
||||||
get_stabilize_pitch(nav_pitch);
|
get_stabilize_pitch(nav_pitch);
|
||||||
|
|
||||||
|
@ -1697,8 +1704,8 @@ void update_roll_pitch_mode(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
// copy latest output from nav controller to stabilize controller
|
// copy latest output from nav controller to stabilize controller
|
||||||
nav_roll = auto_roll;
|
nav_roll += constrain_int32(wrap_180(auto_roll - nav_roll), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second
|
||||||
nav_pitch = auto_pitch;
|
nav_pitch += constrain_int32(wrap_180(auto_pitch - nav_pitch), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second
|
||||||
get_stabilize_roll(nav_roll);
|
get_stabilize_roll(nav_roll);
|
||||||
get_stabilize_pitch(nav_pitch);
|
get_stabilize_pitch(nav_pitch);
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -444,7 +444,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||||
// @DisplayName: Auto Slew Rate
|
// @DisplayName: Auto Slew Rate
|
||||||
// @Description: This restricts the rate of change of the roll and pitch attitude commanded by the auto pilot
|
// @Description: This restricts the rate of change of the roll and pitch attitude commanded by the auto pilot
|
||||||
// @Units: Degrees/Second
|
// @Units: Degrees/Second
|
||||||
// @Range: 1 45
|
// @Range: 1 90
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(auto_slew_rate, "AUTO_SLEW", AUTO_SLEW_RATE),
|
GSCALAR(auto_slew_rate, "AUTO_SLEW", AUTO_SLEW_RATE),
|
||||||
|
|
|
@ -968,7 +968,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef AUTO_SLEW_RATE
|
#ifndef AUTO_SLEW_RATE
|
||||||
# define AUTO_SLEW_RATE 30 // degrees/sec
|
# define AUTO_SLEW_RATE 45 // degrees/sec
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef AUTO_YAW_SLEW_RATE
|
#ifndef AUTO_YAW_SLEW_RATE
|
||||||
|
|
Loading…
Reference in New Issue