ArduPilot / ardupilot

ArduPlane, ArduCopter, ArduRover, ArduSub source
http://ardupilot.org/
GNU General Public License v3.0
10.81k stars 17.27k forks source link

Sanitize Guided WP setting #16483

Open khancyr opened 3 years ago

khancyr commented 3 years ago

Bug report

Issue details

On contrary to Auto mode, we don't sanitize WP on Guided mode. Therefore using something like

    copter.mav.mav.set_position_target_global_int_send(
        0,  # timestamp
        copter.target_system,  # target system_id
        1,  # target component id
        mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE,
        0,  # lat
        0,  # lon
        0,  # alt
        0,  # vx
        0,  # vy
        0,  # vz
        0,  # afx
        0,  # afy
        0,  # afz
        0,  # yaw
        0,  # yawrate
    )

trigger a Panic on SITL.

What should be the best action ?

This was spotted thanks to the help of Nordluft https://www.nordluftautomation.com/

Version Master at https://github.com/ArduPilot/ardupilot/commit/275c2849cf38d32c46e868e7f3e216c8fee5aee7, should be present on current stable release. Plane should be less impacted as it doesn't support position_target_global_int

Platform [ X ] All [ ] AntennaTracker [ ] Copter [ ] Plane [ ] Rover [ ] Submarine

Airframe type What type of airframe (flying wing, glider, hex, Y6, octa etc)

Hardware type What autopilot hardware was used? (Pixhawk, Cube, Pixracer, Navio2, etc)

Logs Please provide a link to any relevant logs that show the issue

rmackay9 commented 3 years ago

I must say that I'm not a fan of interpreting of "0" as the current lat,lon or alt although it could make sense to do that to be consistent with Auto... I guess I would vote for rejecting the command if it is invalid or too far from the current location.

Might be worth dicussing on the devcall if you're planning to add the check.

khancyr commented 3 years ago

Yes, I was assuming that we were rejecting (0, 0) waypoint but that isn't always the case. I am also in favor of answering a rejection instead of silently overriding with the current position.

I note this to not forget it and intend that we discuss it on next EU devcall as that is something important.

peterbarker commented 3 years ago

On Tue, 2 Feb 2021, Pierre Kancir wrote:

Yes, I was assuming that we were rejecting (0, 0) waypoint but that isn't always the case. I am also in favor of answering a rejection instead of silently overriding with the current position.

I note this to not forget it and intend that we discuss it on next EU devcall as that is something important.

FWIW I was looking at whether it was possible to abstract out a method to grab location from a command; lots of places do it ('though not so many _int places... )

hendjoshsr71 commented 3 years ago

Was this discussed on the devcall with an outcome?

I managed to do the same thing with a 0,0,0 position during recent guided testing. I'm guessing rejection is probably the way forward.

tridge commented 2 years ago

discussed on EU dev call, decided we really need an initialised bool on Location rather than assuming 0,0,0 is uninitialised