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

Force arm #4891

Closed
wants to merge 7 commits into from
Closed

Force arm #4891

wants to merge 7 commits into from

Conversation

peterbarker
Copy link
Contributor

@peterbarker peterbarker commented Sep 26, 2016

Passing a parameter value of 2989 through as the second parameter to the long command used to arm a vehicle will bypass the arming checks.

@peterbarker
Copy link
Contributor Author

Why is this a good idea?

Because when ground testing an aircraft it is often useful to not do arming checks - e.g. you haven't attached all the bits of the vehicle or you know you don't need an accurate position.

This is currently accomplished with the equivalent of "set ARMING_CHECK 0" - but that is a persistent change and aircraft have flown with that setting when they shouldn't have.

Using "arm throttle force" (or some clicky-clicky equivalent, I suppose....) is a temporary override reducing the risk of flying with checks disabled.

@khancyr
Copy link
Contributor

khancyr commented Sep 26, 2016

@peterbarker
Agree with you or we can add a warning : arming check disable ! But it miss rover change ;-) .
Could be even better to have a testing mode. When programming a DJI 1000 (can't disconnect motor easily or remove propeller), I got some problem to test failsafe function like landing gear,RTL, and parachute since you need to arm and take off or put throttle and shake uav to put in in-flight state ! Testing mode should allow to test all auto function and failsage on ground without arming motor .

@@ -1455,7 +1455,8 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
case MAV_CMD_COMPONENT_ARM_DISARM:
if (is_equal(packet.param1,1.0f)) {
// run pre_arm_checks and arm_checks and display failures
if (plane.arm_motors(AP_Arming::MAVLINK)) {
const bool do_arming_checks = !is_equal(packet.param2,2989.0f);
Copy link
Contributor

Choose a reason for hiding this comment

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

magic number? Needs to be documented

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'm not sure we document these magic numbers. Note the magic number on disarm force, for example - do we document that anywhere?

Copy link
Contributor

Choose a reason for hiding this comment

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

Ideally as an ardupilot.xml enum. Failing that a #define in GCS.h. But the proper place is a enum with exactly one value :)

copter.init_disarm_motors();
result = MAV_RESULT_ACCEPTED;
} else if (is_zero(packet.param1)) {
if (copter.ap.land_complete || is_equal(packet.param2,21196.0f)) {
Copy link
Contributor

Choose a reason for hiding this comment

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

another magic number?

@dgrat
Copy link
Contributor

dgrat commented Sep 27, 2016

I have strong concerns. Additionally, I don't see a benefit, as the arming checks can be already deactivated.

@OXINARF
Copy link
Member

OXINARF commented Sep 27, 2016

@dgrat What are your concerns? Have you read Peter's second post? He perfectly explains the reasoning behind this: stop people from deactivating arming checks just because they what to arm while bench testing and then flying with the checks deactivated.

@dgrat
Copy link
Contributor

dgrat commented Sep 27, 2016

@OXINARF
Beside that it seems unnecessary because it can be already deactivated by disabling the arming checks in the GCS.
This:

!is_equal(packet.param2,2989.0f);

It doen't really look confident

@OXINARF
Copy link
Member

OXINARF commented Sep 27, 2016

Beside that it seems unnecessary because it can be already deactivated by disabling the arming checks in the GCS.

And it has been explained why that is a bad option...

It doen't really look confident

What does this mean?

@dgrat
Copy link
Contributor

dgrat commented Sep 27, 2016

@OXINARF
The implementation is weak, and this is why I think so:

  • The magic number definition could be at least put in a macro definition to enhance readability
  • The new MAVLink function takes two bools now, both containing a variable switching the arming
    • This looks lazy: (const bool arming_from_gcs, const bool do_arming_checks)
    • I am sure this can be solved in a more elegant manner
  • I don't like the fact that someone uses float for '==' comparisons (in general)
    • Maybe convert it into an integer instead to be lazy using is_equal(), which I just added to the math-backend because of compatibility reasons ):

@magicrub
Copy link
Contributor

I think casting the float to int32 is perfectly fine, we should do that in more places on mavlink params. Also, I pointed out the magic number thing, definitely needs to be documented via define const or something

@R-Lefebvre
Copy link
Contributor

I think this is a good idea. I too often am looking at my parameters and realizing "Oops, this is another one that I turned off arming checks and forgot to reset!"

If this PR isn't merged, then I would at least like it if we could have something where, when doing standard arming with checks defeated, instead of just saying "Armed" the GCS will display something like "Armed. All checks defeated."

@OXINARF
Copy link
Member

OXINARF commented Sep 28, 2016

@dgrat

The magic number definition could be at least put in a macro definition to enhance readability

I don't have an issue with that, although this isn't something we want people to use in normal operation, so it being hidden in code isn't that bad.

The new MAVLink function takes two bools now, both containing a variable switching the arming

They have different meanings, how would you propose to do it differently?

I don't like the fact that someone uses float for '==' comparisons

I agree with that, but you should understand that it is transmitted in MAVLink as a float. Also, this isn't a safety problem, so if the check fails for some reason it isn't critical.

@peterbarker Have you though about adding a new command instead of adding a new magical number? MAVLink has MAV_CMD_DO_FLIGHTTERMINATION which should now be used instead of the magical number, maybe it could have a MAV_CMD_DO_FLIGHTTESTING or something like that?

@dgrat
Copy link
Contributor

dgrat commented Sep 28, 2016

@OXINARF

I agree with that, but you should understand that it is transmitted in MAVLink as a float. Also, this isn't a safety problem, so if the check fails for some reason it isn't critical.

Agree, but still it isn't the optimal solution.

@rmackay9
Copy link
Contributor

rmackay9 commented Oct 5, 2016

I'm happy with this but there's one serious danger which is that I think it allows arming in Loiter, PosHold, etc when the EKF doesn't have a position estimate. We should not allow this under any circumstances because I think the vehicle could act very badly. I'm not sure what it will do actually.

@peterbarker
Copy link
Contributor Author

@R-Lefebvre In regards to the "all checks defeated" warning you suggest - I actually added that to MAVProxy a few weeks back, 'though it actually just says, "arming checks disabled" if you have any checks disabled.

@peterbarker
Copy link
Contributor Author

@OXINARF The shape of this patch is based on the existing "force disarm" functionality: https://github.com/ArduPilot/ardupilot/blob/master/ArduCopter/GCS_Mavlink.cpp#L1432

Note the use of magic numbers, and abusing random positional parameters to achieve a specific outcome :-)

@peterbarker
Copy link
Contributor Author

@rmackay9 That sounds like fun. I would assume EKF would drop you into stabilize or land-without-gps mode.

But that's what "force" is for. It says you're happy to pretend you know what you're doing and will wear the consequences...

I would prefer to keep "force arming" a true force, but we could instead pass a bitmask around of checks to enforce in copter, passing through an empty mask if force is set.

@OXINARF
Copy link
Member

OXINARF commented Oct 5, 2016

I agree that a Force Arm should force arm no matter what. Otherwise it isn't a real force and we'll have requests to have a method to arm in any mode.

@peterbarker I know that this follows the same logic of the magic follow disarm, but that is a deprecated method. The new method is using a specific message, which I think should be the way to go with this.

@peterbarker
Copy link
Contributor Author

@DonLakeFlyer @billbonney @meee1 Could I ask you to weigh in here, please?

Executeive summay - question is how we should implement a "force arm". There are two options:

  • implement it just as we do "force disarm" (a magic number in one of the parameters to MAV_CMD_COMPONENT_ARM_DISARM
  • create a new mavlink message, analogous to MAV_CMD_DO_FLIGHTTERMINATION

I'm not convinced a force-arm is the opposite of a MAV_CMD_DO_FLIGHTTERMINATION. In the OBC context, a FLIGHTTERMINATION is somewhat more serious thing to do to a plane than a disarm (setting control surfaces to maximum deflection etc etc). It is definitely the opposite of a force-disarm, however.

I'm asking your opinions here because all the GCS implementations I've looked at use the magic-number approach. No point making this force-arm change if the GCS aren't going to implement it. Modifying them to allow force-arm (a shift-click on arm, perhaps?) is going to be a relatively small change.

@lvale
Copy link
Member

lvale commented May 8, 2017

@peterbarker If this goes forward I believe that there should be a audible and visual warning for as long as the vehicle is armed in forced mode, so that users get notified of the extraordinary condition on which the vehicle was armed.

@DonLakeFlyer
Copy link
Contributor

My feeling is that options which will be used/found by 1% of the user base should not be added.

@peterbarker
Copy link
Contributor Author

peterbarker commented May 9, 2017 via email

@peterbarker
Copy link
Contributor Author

I've updated this to pull out the magic values into variables.

@rmackay9
Copy link
Contributor

rmackay9 commented Jun 7, 2017

We just need to make sure that some checks are still applied for copter. For example, it shouldn't be possible to arm in Loiter with no position estimate (i.e. no GPS). no matter how much the user thinks they want that, it would be a very bad result that would end in tears.

@OXINARF
Copy link
Member

OXINARF commented Jun 7, 2017

@rmackay9, you are the Copter maintainer, so you have the final word, but I strongly disagree with that. The disarming magic doesn't force any checks, and if this is going to force checks then we don't need it, we already have an arming method.

For example, it shouldn't be possible to arm in Loiter with no position estimate (i.e. no GPS). no matter how much the user thinks they want that

What prevents the user doing that now by disabling the arming checks?

I understand the concern of having this, but it should be deeply hidden in any GCS. The disarm aux switch looks way more dangerous to me and that went in. The forced disarm is always sent by MP when pressing the disarm button, which also looks more dangerous to me.

@peterbarker
Copy link
Contributor Author

@lvale audible alarm when force-armed? You would also be OK with a MUCH LOUDER alarm if their arming-checks parameter is zero, then? Because 3/4 of the logs I see have them disabled - it's a "set and forget" way of making your problems go away, and I'm pretty sure the "forget" part is real.

@peterbarker
Copy link
Contributor Author

I've verified that if you do not have position when arming in loiter/poshold then the vehicle behaves appropriately - mode land, disarm.

@peterbarker
Copy link
Contributor Author

It was agreed on the dev-call to merge this in. I accidentally closed this issue before it was merged in - I've now pushed it in.

@rmackay9
Copy link
Contributor

As a side note, personally I prefer #defines rather than constants. The reason is just that I find them easier to differentiate from regular variables because they're normally in caps.

@peterbarker
Copy link
Contributor Author

@rmackay9 You can have these variables in CAPS, too :-) That gives you type-safety, namespacing and differentiation. IIRC I did try it on for size once - but somebody didn't like it...

@WickedShell
Copy link
Contributor

Either way if we make a MAVLink enum for it that can replace the constants anyways :)

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