Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

manual speed input for quadplanes #11548

Closed
wants to merge 3 commits into from
Closed

Conversation

kd0aij
Copy link
Contributor

@kd0aij kd0aij commented Jun 10, 2019

Allows using an RC input channel to control the forward speed in QHOVER mode and forward throttle directly in QACRO and QSTABILIZE modes.
Also adds manual rudder control in QACRO and QSTABILIZE
supersedes #11378

implement speed bias for QHOVER and QSTABILIZE modes
add @RebootRequired to metadata for param Q_SPD_BIAS_CH
scale manual tilt bias to Q_TILT_MAX
@@ -42,5 +42,8 @@ void ModeQStabilize::update()

plane.nav_roll_cd = (plane.channel_roll->get_control_in() / 4500.0) * roll_limit;
plane.nav_roll_cd = constrain_int32(plane.nav_roll_cd, -roll_limit, roll_limit);

// set rudder using stick
plane.steering_control.rudder = plane.channel_rudder->get_control_in();
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This would overdrive/destablize the quad tuning on a lot of quadplanes, and has a huge impact based on what the wind over the surface is, I don't think this is a safe change.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Particular example being that on my system the rudder is normally only used for ~15% of it's output range, but if you mapped the input directly onto that it would have much larger yaw moments then the quad tuning is expecting, but it would be highly dependent upon the wind (really forward airspeed)

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@WickedShell Thanks for commenting!
Definitely need to address stability when zooming along at 15 m/sec in Qmodes...
I have another PR which implements gain scaling for tailsitters to deal with high airspeed: #11195
but I haven't yet thought about whether that can work for non-tailsitters.
I found I was unable to turn without rudder though

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

As I think I described to you we do the wrong thing with the rudder in some modes and nothing in others, so I do want to see us use it. It's just that this won't work out well for existing setups and actively hurts quadplanes that are currently tuned. If it's restricted to QAcro it wouldn't bother me as much, but this would have a very negative impact in flying current quadplane tuning through the full range of winds the aircraft can otherwise handle.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I changed the rudder control to motors->get_yaw
That is the demand from the copter controller, and it tests OK in SITL

add rudder control: direct for qacro and copter controller for qstabilize
@kd0aij
Copy link
Contributor Author

kd0aij commented Jul 10, 2019

replaced by #11763

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

2 participants